From 38b8e946e6efc4a0e63ae9a9301b847597a6a4e6 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Fri, 24 Nov 2023 20:19:01 +0100 Subject: [PATCH 01/14] feat(#78): Added test for sensor precision of GPS and IMU --- build/docker-compose.yml | 4 +- code/acting/launch/acting.launch | 20 +- code/agent/config/dev_objects.json | 49 +++++ code/agent/config/rviz_config.rviz | 2 +- code/perception/launch/perception.launch | 6 + code/perception/src/dataset_generator.py | 17 +- code/perception/src/lidar_filter_utility.py | 0 code/perception/src/sensor_filter_debug.py | 198 ++++++++++++++++++++ 8 files changed, 272 insertions(+), 24 deletions(-) mode change 100644 => 100755 code/perception/src/dataset_generator.py mode change 100644 => 100755 code/perception/src/lidar_filter_utility.py create mode 100755 code/perception/src/sensor_filter_debug.py diff --git a/build/docker-compose.yml b/build/docker-compose.yml index baf7d008..fd0e7069 100644 --- a/build/docker-compose.yml +++ b/build/docker-compose.yml @@ -54,8 +54,8 @@ services: tty: true shm_size: 2gb #command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/opt/leaderboard/leaderboard/autoagents/npc_agent.py --host=carla-simulator --track=SENSORS" - #command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" - command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" + command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" + #command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" logging: driver: "local" environment: diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index dc276494..df4979fb 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -28,30 +28,32 @@ - + - + - + - + + - + - + + + diff --git a/code/agent/config/dev_objects.json b/code/agent/config/dev_objects.json index cafac343..370308aa 100644 --- a/code/agent/config/dev_objects.json +++ b/code/agent/config/dev_objects.json @@ -179,6 +179,55 @@ { "type": "actor.pseudo.control", "id": "control" + }, + { + "type": "sensor.other.gnss", + "id": "Ideal_GPS", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 1.60 + }, + "noise_alt_stddev": 0.0, + "noise_lat_stddev": 0.0, + "noise_lon_stddev": 0.0, + "noise_alt_bias": 0.0, + "noise_lat_bias": 0.0, + "noise_lon_bias": 0.0 + }, + { + "type": "sensor.other.imu", + "id": "Ideal_IMU", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "noise_accel_stddev_x": 0.0, + "noise_accel_stddev_y": 0.0, + "noise_accel_stddev_z": 0.0, + "noise_gyro_stddev_x": 0.0, + "noise_gyro_stddev_y": 0.0, + "noise_gyro_stddev_z": 0.0 + }, + { + "type": "sensor.other.radar", + "id": "Ideal_RADAR", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": -45.0 + }, + "horizontal_fov": 30.0, + "vertical_fov": 30.0, + "points_per_second": 1500, + "range": 100.0 } ] } diff --git a/code/agent/config/rviz_config.rviz b/code/agent/config/rviz_config.rviz index 60da1674..b6d02247 100644 --- a/code/agent/config/rviz_config.rviz +++ b/code/agent/config/rviz_config.rviz @@ -149,7 +149,7 @@ Visualization Manager: Offset: X: 0 Y: 0 - Z: 39 + Z: 0 #39 Pose Color: 255; 85; 255 Pose Style: None Queue Size: 10 diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index bc8c8f9c..eb94eef9 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -2,6 +2,12 @@ + + + + + + diff --git a/code/perception/src/dataset_generator.py b/code/perception/src/dataset_generator.py old mode 100644 new mode 100755 index fd849d11..58f5d4b4 --- a/code/perception/src/dataset_generator.py +++ b/code/perception/src/dataset_generator.py @@ -246,21 +246,15 @@ def create_argparse(): help='set up an empty world and spawn ego vehicle', default=False ) - argparser.add_argument( - '--town', - metavar='T', - default='Town12', - help='town to load' - ) return argparser if __name__ == '__main__': - towns = {"Town01", "Town02", "Town03", "Town04", "Town05", "Town06", - "Town07", "Town10", "Town11", "Town12"} + towns = ["Town01", "Town02", "Town03", "Town04", "Town05", "Town06", + "Town07", "Town10", "Town11", "Town12"] + town = towns[2] argparser = create_argparse() args = argparser.parse_args() - town = args.town output_dir = args.output_dir host = args.host port = args.port @@ -268,11 +262,10 @@ def create_argparse(): client = carla.Client(host, port) client.set_timeout(30) - world = client.load_world(town) if use_empty_world else client.get_world() + world = client.load_world(town) world.wait_for_tick() - output_dir = os.path.join(output_dir, world.get_map().name[-2:]) - print("Saving images to {}".format(output_dir)) + output_dir = os.path.join(output_dir, town[-2:]) if use_empty_world: ego_vehicle = setup_empty_world(client) diff --git a/code/perception/src/lidar_filter_utility.py b/code/perception/src/lidar_filter_utility.py old mode 100644 new mode 100755 diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py new file mode 100755 index 00000000..84c8d991 --- /dev/null +++ b/code/perception/src/sensor_filter_debug.py @@ -0,0 +1,198 @@ +#!/usr/bin/env python + +""" +This node publishes all relevant topics for the ekf node. +""" +import math +import numpy as np +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from geometry_msgs.msg import PoseStamped +from sensor_msgs.msg import NavSatFix, Imu +from nav_msgs.msg import Odometry +from std_msgs.msg import Float32 +from coordinate_transformation import CoordinateTransformer, GeoRef +from tf.transformations import euler_from_quaternion + +GPS_RUNNING_AVG_ARGS: int = 10 + + +class PositionPublisherNode(CompatibleNode): + """ + Node publishes a filtered gps signal. + This is achieved using a rolling average. + """ + + def __init__(self): + """ + Constructor / Setup + :return: + """ + + super(PositionPublisherNode, self).__init__('ekf_translation') + self.loginfo("Position publisher node started") + + # basic info + self.role_name = self.get_param("role_name", "hero") + self.control_loop_rate = self.get_param("control_loop_rate", "0.05") + + # todo: automatically detect town + self.transformer = CoordinateTransformer(GeoRef.TOWN12) + + # Subscriber + self.imu_subscriber = self.new_subscription( + Imu, + "/carla/" + self.role_name + "/Ideal_IMU", + self.update_imu_data, + qos_profile=1) + + self.gps_subscriber = self.new_subscription( + NavSatFix, + "/carla/" + self.role_name + "/Ideal_GPS", + self.update_gps_data, + qos_profile=1) + + # Publisher + # 2D Odometry (Maybe Speedometer?) + self.ekf_odom_publisher = self.new_publisher( + Odometry, + "/ideal_odom", + qos_profile=1) + + # IMU + self.ekf_imu_publisher = self.new_publisher( + Imu, + "/ideal_imu_data", + qos_profile=1) + + self.avg_xyz = np.zeros((GPS_RUNNING_AVG_ARGS, 3)) + self.avg_gps_counter: int = 0 + # 3D Odometry (GPS) + self.cur_pos_publisher = self.new_publisher( + PoseStamped, + f"/paf/{self.role_name}/ideal_current_pos", + qos_profile=1) + + self.__heading: float = 0 + self.__heading_publisher = self.new_publisher( + Float32, + f"/paf/{self.role_name}/ideal_current_heading", + qos_profile=1) + + def update_imu_data(self, data: Imu): + """ + This method is called when new IMU data is received. + It handles all necessary updates and publishes the heading. + :param data: new IMU measurement + :return: + """ + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + def update_gps_data(self, data: NavSatFix): + """ + This method is called when new GNSS data is received. + The function calculates the average position and then publishes it. + Measurements are also transformed to global xyz-coordinates + :param data: GNSS measurement + :return: + """ + lat = data.latitude + lon = data.longitude + alt = data.altitude + x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + # find reason for discrepancy + x *= 0.998 + y *= 1.003 + + self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) + self.avg_xyz[-1] = np.matrix([x, y, z]) + + avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) + + cur_pos = PoseStamped() + + cur_pos.header.stamp = data.header.stamp + cur_pos.header.frame_id = "global" + + cur_pos.pose.position.x = avg_x + cur_pos.pose.position.y = avg_y + cur_pos.pose.position.z = avg_z + + cur_pos.pose.orientation.x = 0 + cur_pos.pose.orientation.y = 0 + cur_pos.pose.orientation.z = 1 + cur_pos.pose.orientation.w = 0 + + self.cur_pos_publisher.publish(cur_pos) + + def run(self): + """ + Control loop + :return: + """ + self.spin() + + +def main(args=None): + """ + main function + :param args: + :return: + """ + + roscomp.init("position_publisher_node_2", args=args) + try: + node = PositionPublisherNode() + node.run() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() + + +if __name__ == "__main__": + main() From d1f6183a060ab565287a2a7951d90352ed0346d0 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 16:06:35 +0100 Subject: [PATCH 02/14] feat(#78): GPS and IMU debug finished Added error_publisher for both heading_error (IMU Sensor) and location_error (GPS Sensor) --- code/acting/launch/acting.launch | 3 +- code/perception/launch/perception.launch | 3 + code/perception/src/sensor_filter_debug.py | 166 +++++++++++++++++++++ 3 files changed, 171 insertions(+), 1 deletion(-) diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index df4979fb..42ff7b9b 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -55,5 +55,6 @@ - + + diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index eb94eef9..9d3d0d12 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -53,4 +53,7 @@ + + + diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 84c8d991..1ae1eed0 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -13,6 +13,11 @@ from std_msgs.msg import Float32 from coordinate_transformation import CoordinateTransformer, GeoRef from tf.transformations import euler_from_quaternion +from std_msgs.msg import Float32MultiArray + +import carla +import rospy +#from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -22,6 +27,7 @@ class PositionPublisherNode(CompatibleNode): Node publishes a filtered gps signal. This is achieved using a rolling average. """ + def __init__(self): """ @@ -30,6 +36,11 @@ def __init__(self): """ super(PositionPublisherNode, self).__init__('ekf_translation') + #self.current_pos = PoseStamped() + self.ideal_corrent_pos = PoseStamped() + self.carla_current_pos = PoseStamped() + self.ideal_imu_data = Imu() + self.loginfo("Position publisher node started") # basic info @@ -79,6 +90,135 @@ def __init__(self): f"/paf/{self.role_name}/ideal_current_heading", qos_profile=1) + # Carla API hero car position + # Get parameters from the launch file + host = rospy.get_param('~host', 'carla-simulator') + port = rospy.get_param('~port', 2000) + timeout = rospy.get_param('~timeout', 100.0) + role_name = rospy.get_param('~role_name', 'hero') + + # Connect to the CARLA server + client = carla.Client(host, port) + client.set_timeout(timeout) + + # Get the world + self.world = client.get_world() + + # Get the ego vehicle + self.vehicle = None + + + # Publish the location + self.carla_pos_publisher = self.new_publisher( + PoseStamped, + f"/paf/{self.role_name}/carla_current_pos", + qos_profile=1) + + # Error Publisher + # publish error distance between current_pos and ideal_corrent_pos & current_pos and carla_current_pos: + # current_pos and ideal_corrent_pos in location_error[0] + # current_pos and carla_current_pos in location_error[1] + self.locoation_error_publisher = self.new_publisher( + Float32MultiArray, + f"/paf/{self.role_name}/location_error", + qos_profile=1) + # Current_pos subscriber: + self.current_pos_subscriber = self.new_subscription( + PoseStamped, + f"/paf/{self.role_name}/current_pos", + self.update_location_error, + qos_profile=1) + + """ + # publish the error between imu and ideal_imu + self.imu_error_publisher = self.new_publisher( + Float32, + f"/paf/{self.role_name}/imu_error", + qos_profile=1) + + # Imu subscriber: + self.imu_subscriber = self.new_subscription( + Imu, + f"/carla/{self.role_name}/IMU", + self.update_imu_error, + qos_profile=1) + """ + """ + def update_imu_error(self, data: Imu): + ""'" + This method is called when new IMU data is received. + It handles all necessary updates and publishes the heading. + :param data: new IMU measurement + :return: + ""'" + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + # calculate the error between ideal_imu and imu + error = Float32() + error.data = math.sqrt((self.ideal_imu_data + """ + + def update_location_error(self, data: PoseStamped): + """ + This method is called when new current_pos data is received. + It handles all necessary updates and publishes the error. + :param data: new current_pos measurement + :return: + """ + + error = Float32MultiArray() + #error.layout.dim = [0, 0] + error.data = [0, 0] + # calculate the error between ideal_current_pos and current_pos + error.data[0] = math.sqrt((self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) + # calculate the error between carla_current_pos and current_pos + error.data[1] = math.sqrt((self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) + self.error_publisher.publish(error) + def update_imu_data(self, data: Imu): """ This method is called when new IMU data is received. @@ -168,6 +308,32 @@ def update_gps_data(self, data: NavSatFix): cur_pos.pose.orientation.w = 0 self.cur_pos_publisher.publish(cur_pos) + self.ideal_current_pos = cur_pos + + # also update carla_car_position: + if self.vehicle is None: + for actor in self.world.get_actors(): + if actor.attributes.get('role_name') == self.role_name: + self.vehicle = actor + break + + + carla_pos = PoseStamped() + carla_pos.header.stamp = data.header.stamp + carla_pos.header.frame_id = "global" + + pos = self.vehicle.get_location() + carla_pos.pose.position.x = pos.x + carla_pos.pose.position.y = -pos.y + carla_pos.pose.position.z = pos.z + + carla_pos.pose.orientation.x = 0 + carla_pos.pose.orientation.y = 0 + carla_pos.pose.orientation.z = 1 + carla_pos.pose.orientation.w = 0 + + self.carla_pos_publisher.publish(carla_pos) + self.carla_current_pos = carla_pos def run(self): """ From 62dc437a8bc8205359e2bef68fa5eb4686b0f0a2 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 16:08:29 +0100 Subject: [PATCH 03/14] feat(#78): GPS and IMU debug finished Added error_publisher for both heading_error (IMU Sensor) and location_error (GPS Sensor) --- code/perception/src/sensor_filter_debug.py | 229 +++++++++------------ 1 file changed, 92 insertions(+), 137 deletions(-) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 1ae1eed0..dbc3c6ff 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -17,7 +17,7 @@ import carla import rospy -#from carla_msgs.msg import CarlaLo +# from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -27,8 +27,6 @@ class PositionPublisherNode(CompatibleNode): Node publishes a filtered gps signal. This is achieved using a rolling average. """ - - def __init__(self): """ Constructor / Setup @@ -36,10 +34,10 @@ def __init__(self): """ super(PositionPublisherNode, self).__init__('ekf_translation') - #self.current_pos = PoseStamped() + # self.current_pos = PoseStamped() self.ideal_corrent_pos = PoseStamped() self.carla_current_pos = PoseStamped() - self.ideal_imu_data = Imu() + self.ideal_heading = Float32() self.loginfo("Position publisher node started") @@ -95,7 +93,6 @@ def __init__(self): host = rospy.get_param('~host', 'carla-simulator') port = rospy.get_param('~port', 2000) timeout = rospy.get_param('~timeout', 100.0) - role_name = rospy.get_param('~role_name', 'hero') # Connect to the CARLA server client = carla.Client(host, port) @@ -107,100 +104,52 @@ def __init__(self): # Get the ego vehicle self.vehicle = None - # Publish the location self.carla_pos_publisher = self.new_publisher( PoseStamped, f"/paf/{self.role_name}/carla_current_pos", qos_profile=1) - - # Error Publisher - # publish error distance between current_pos and ideal_corrent_pos & current_pos and carla_current_pos: - # current_pos and ideal_corrent_pos in location_error[0] - # current_pos and carla_current_pos in location_error[1] - self.locoation_error_publisher = self.new_publisher( + + # Error Publisher + """publish error distance between current_pos and ideal_corrent_pos & + current_pos and carla_current_pos: + # current_pos and ideal_corrent_pos in location_error[0] + # current_pos and carla_current_pos in location_error[1] + """ + self.location_error_publisher = self.new_publisher( Float32MultiArray, f"/paf/{self.role_name}/location_error", qos_profile=1) + # Current_pos subscriber: self.current_pos_subscriber = self.new_subscription( PoseStamped, f"/paf/{self.role_name}/current_pos", self.update_location_error, qos_profile=1) - - """ - # publish the error between imu and ideal_imu - self.imu_error_publisher = self.new_publisher( + + # publish the error between current_heading and ideal_heading + self.heading_error_publisher = self.new_publisher( Float32, - f"/paf/{self.role_name}/imu_error", + f"/paf/{self.role_name}/heading_error", qos_profile=1) - - # Imu subscriber: - self.imu_subscriber = self.new_subscription( - Imu, - f"/carla/{self.role_name}/IMU", - self.update_imu_error, - qos_profile=1) - """ - """ - def update_imu_error(self, data: Imu): - ""'" - This method is called when new IMU data is received. - It handles all necessary updates and publishes the heading. - :param data: new IMU measurement - :return: - ""'" - imu_data = Imu() - - imu_data.header.stamp = data.header.stamp - imu_data.header.frame_id = "hero" - imu_data.orientation.x = data.orientation.x - imu_data.orientation.y = data.orientation.y - imu_data.orientation.z = data.orientation.z - imu_data.orientation.w = data.orientation.w - imu_data.orientation_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.angular_velocity.x = data.angular_velocity.x - imu_data.angular_velocity.y = data.angular_velocity.y - imu_data.angular_velocity.z = data.angular_velocity.z - imu_data.angular_velocity_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.linear_acceleration.x = data.linear_acceleration.x - imu_data.linear_acceleration.y = data.linear_acceleration.y - imu_data.linear_acceleration.z = data.linear_acceleration.z - imu_data.linear_acceleration_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - self.ekf_imu_publisher.publish(imu_data) - - # Calculate the heading based on the orientation given by the IMU - data_orientation_q = [data.orientation.x, - data.orientation.y, - data.orientation.z, - data.orientation.w] + # Current_heading subscriber: + self.current_heading_subscriber = self.new_subscription( + Float32, + f"/paf/{self.role_name}/current_heading", + self.update_heading_error, + qos_profile=1) - roll, pitch, yaw = euler_from_quaternion(data_orientation_q) - raw_heading = math.atan2(roll, pitch) + def update_heading_error(self, data: Float32): + """ + This method is called when new current_heading data is received. + """ + current_heading = data.data - # transform raw_heading so that: - # --------------------------------------------------------------- - # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | - # --------------------------------------------------------------- - heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi - self.__heading = heading - self.__heading_publisher.publish(self.__heading) - # calculate the error between ideal_imu and imu - error = Float32() - error.data = math.sqrt((self.ideal_imu_data - """ + heading_error = self.ideal_heading.data - current_heading + self.heading_error_publisher.publish(heading_error) def update_location_error(self, data: PoseStamped): """ @@ -211,66 +160,18 @@ def update_location_error(self, data: PoseStamped): """ error = Float32MultiArray() - #error.layout.dim = [0, 0] + # error.layout.dim = [0, 0] error.data = [0, 0] # calculate the error between ideal_current_pos and current_pos - error.data[0] = math.sqrt((self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) + error.data[0] = math.sqrt(( + self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) # calculate the error between carla_current_pos and current_pos - error.data[1] = math.sqrt((self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) - self.error_publisher.publish(error) + error.data[1] = math.sqrt(( + self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) - def update_imu_data(self, data: Imu): - """ - This method is called when new IMU data is received. - It handles all necessary updates and publishes the heading. - :param data: new IMU measurement - :return: - """ - imu_data = Imu() - - imu_data.header.stamp = data.header.stamp - imu_data.header.frame_id = "hero" - - imu_data.orientation.x = data.orientation.x - imu_data.orientation.y = data.orientation.y - imu_data.orientation.z = data.orientation.z - imu_data.orientation.w = data.orientation.w - imu_data.orientation_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.angular_velocity.x = data.angular_velocity.x - imu_data.angular_velocity.y = data.angular_velocity.y - imu_data.angular_velocity.z = data.angular_velocity.z - imu_data.angular_velocity_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.linear_acceleration.x = data.linear_acceleration.x - imu_data.linear_acceleration.y = data.linear_acceleration.y - imu_data.linear_acceleration.z = data.linear_acceleration.z - imu_data.linear_acceleration_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - self.ekf_imu_publisher.publish(imu_data) - - # Calculate the heading based on the orientation given by the IMU - data_orientation_q = [data.orientation.x, - data.orientation.y, - data.orientation.z, - data.orientation.w] - - roll, pitch, yaw = euler_from_quaternion(data_orientation_q) - raw_heading = math.atan2(roll, pitch) - - # transform raw_heading so that: - # --------------------------------------------------------------- - # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | - # --------------------------------------------------------------- - heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi - self.__heading = heading - self.__heading_publisher.publish(self.__heading) + self.location_error_publisher.publish(error) def update_gps_data(self, data: NavSatFix): """ @@ -317,7 +218,6 @@ def update_gps_data(self, data: NavSatFix): self.vehicle = actor break - carla_pos = PoseStamped() carla_pos.header.stamp = data.header.stamp carla_pos.header.frame_id = "global" @@ -335,6 +235,61 @@ def update_gps_data(self, data: NavSatFix): self.carla_pos_publisher.publish(carla_pos) self.carla_current_pos = carla_pos + def update_imu_data(self, data: Imu): + """ + This method is called when new IMU data is received. + The function calculates the average position and then publishes it. + :param data: IMU measurement + :return: + """ + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + self.ideal_heading = Float32(heading) + def run(self): """ Control loop From 632d3bc844c5014089520ec8ce1f81313bd5fc2f Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 20:09:14 +0100 Subject: [PATCH 04/14] feat(#78): fixed optimal GPS --- code/agent/config/dev_objects.json | 2 +- code/perception/src/sensor_filter_debug.py | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/code/agent/config/dev_objects.json b/code/agent/config/dev_objects.json index 370308aa..90b24361 100644 --- a/code/agent/config/dev_objects.json +++ b/code/agent/config/dev_objects.json @@ -222,7 +222,7 @@ "z": 1.60, "roll": 0.0, "pitch": 0.0, - "yaw": -45.0 + "yaw": 45.0 }, "horizontal_fov": 30.0, "vertical_fov": 30.0, diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index dbc3c6ff..fce6371f 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -35,7 +35,7 @@ def __init__(self): super(PositionPublisherNode, self).__init__('ekf_translation') # self.current_pos = PoseStamped() - self.ideal_corrent_pos = PoseStamped() + self.ideal_current_pos = PoseStamped() self.carla_current_pos = PoseStamped() self.ideal_heading = Float32() @@ -189,19 +189,19 @@ def update_gps_data(self, data: NavSatFix): x *= 0.998 y *= 1.003 - self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) - self.avg_xyz[-1] = np.matrix([x, y, z]) + # self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) + # self.avg_xyz[-1] = np.matrix([x, y, z]) - avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) + # avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) cur_pos = PoseStamped() cur_pos.header.stamp = data.header.stamp cur_pos.header.frame_id = "global" - cur_pos.pose.position.x = avg_x - cur_pos.pose.position.y = avg_y - cur_pos.pose.position.z = avg_z + cur_pos.pose.position.x = x + cur_pos.pose.position.y = y + cur_pos.pose.position.z = z cur_pos.pose.orientation.x = 0 cur_pos.pose.orientation.y = 0 From 609b5f5a52c788b7bb3bc3bbb5c7e48dcc65416c Mon Sep 17 00:00:00 2001 From: robertik10 Date: Tue, 28 Nov 2023 16:57:48 +0100 Subject: [PATCH 05/14] feat(#78): new coordinate Transformation package --- code/perception/src/sensor_filter_debug.py | 6 +++++- code/requirements.txt | 1 + 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index fce6371f..394789e4 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -17,6 +17,7 @@ import carla import rospy +import pymap3d as pm # from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -184,7 +185,10 @@ def update_gps_data(self, data: NavSatFix): lat = data.latitude lon = data.longitude alt = data.altitude - x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + # x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + lonref, latref, altref = GeoRef.TOWN12.value + x, y, z = pm.geodetic2enu(lat, lon, alt, + lonref, latref, altref) # find reason for discrepancy x *= 0.998 y *= 1.003 diff --git a/code/requirements.txt b/code/requirements.txt index 5c78ad34..3d913b89 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -18,3 +18,4 @@ scipy==1.10.0 xmltodict==0.13.0 py-trees==2.1.6 numpy==1.23.5 +pymap3d==3.0.0 From 01f34ad529e7571ac680faf673f01a3298b728fc Mon Sep 17 00:00:00 2001 From: robertik10 Date: Fri, 24 Nov 2023 20:19:01 +0100 Subject: [PATCH 06/14] feat(#78): Added test for sensor precision of GPS and IMU --- build/docker-compose.yml | 4 +- code/acting/launch/acting.launch | 20 +- code/agent/config/dev_objects.json | 49 +++++ code/agent/config/rviz_config.rviz | 2 +- code/perception/launch/perception.launch | 6 + code/perception/src/dataset_generator.py | 17 +- code/perception/src/lidar_filter_utility.py | 0 code/perception/src/sensor_filter_debug.py | 198 ++++++++++++++++++++ 8 files changed, 272 insertions(+), 24 deletions(-) mode change 100644 => 100755 code/perception/src/dataset_generator.py mode change 100644 => 100755 code/perception/src/lidar_filter_utility.py create mode 100755 code/perception/src/sensor_filter_debug.py diff --git a/build/docker-compose.yml b/build/docker-compose.yml index a68e97c4..2f5c93ac 100644 --- a/build/docker-compose.yml +++ b/build/docker-compose.yml @@ -57,8 +57,8 @@ services: tty: true shm_size: 2gb #command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/opt/leaderboard/leaderboard/autoagents/npc_agent.py --host=carla-simulator --track=SENSORS" - #command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" - command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" + command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" + #command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" logging: driver: "local" environment: diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index dc276494..df4979fb 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -28,30 +28,32 @@ - + - + - + - + + - + - + + + diff --git a/code/agent/config/dev_objects.json b/code/agent/config/dev_objects.json index cafac343..370308aa 100644 --- a/code/agent/config/dev_objects.json +++ b/code/agent/config/dev_objects.json @@ -179,6 +179,55 @@ { "type": "actor.pseudo.control", "id": "control" + }, + { + "type": "sensor.other.gnss", + "id": "Ideal_GPS", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 1.60 + }, + "noise_alt_stddev": 0.0, + "noise_lat_stddev": 0.0, + "noise_lon_stddev": 0.0, + "noise_alt_bias": 0.0, + "noise_lat_bias": 0.0, + "noise_lon_bias": 0.0 + }, + { + "type": "sensor.other.imu", + "id": "Ideal_IMU", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "noise_accel_stddev_x": 0.0, + "noise_accel_stddev_y": 0.0, + "noise_accel_stddev_z": 0.0, + "noise_gyro_stddev_x": 0.0, + "noise_gyro_stddev_y": 0.0, + "noise_gyro_stddev_z": 0.0 + }, + { + "type": "sensor.other.radar", + "id": "Ideal_RADAR", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": -45.0 + }, + "horizontal_fov": 30.0, + "vertical_fov": 30.0, + "points_per_second": 1500, + "range": 100.0 } ] } diff --git a/code/agent/config/rviz_config.rviz b/code/agent/config/rviz_config.rviz index 7064cc88..0d43d6b1 100644 --- a/code/agent/config/rviz_config.rviz +++ b/code/agent/config/rviz_config.rviz @@ -166,7 +166,7 @@ Visualization Manager: Offset: X: 0 Y: 0 - Z: 39 + Z: 0 #39 Pose Color: 255; 85; 255 Pose Style: None Queue Size: 10 diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index cf3d5ae6..e9d99ba2 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -2,6 +2,12 @@ + + + + + + diff --git a/code/perception/src/dataset_generator.py b/code/perception/src/dataset_generator.py old mode 100644 new mode 100755 index fd849d11..58f5d4b4 --- a/code/perception/src/dataset_generator.py +++ b/code/perception/src/dataset_generator.py @@ -246,21 +246,15 @@ def create_argparse(): help='set up an empty world and spawn ego vehicle', default=False ) - argparser.add_argument( - '--town', - metavar='T', - default='Town12', - help='town to load' - ) return argparser if __name__ == '__main__': - towns = {"Town01", "Town02", "Town03", "Town04", "Town05", "Town06", - "Town07", "Town10", "Town11", "Town12"} + towns = ["Town01", "Town02", "Town03", "Town04", "Town05", "Town06", + "Town07", "Town10", "Town11", "Town12"] + town = towns[2] argparser = create_argparse() args = argparser.parse_args() - town = args.town output_dir = args.output_dir host = args.host port = args.port @@ -268,11 +262,10 @@ def create_argparse(): client = carla.Client(host, port) client.set_timeout(30) - world = client.load_world(town) if use_empty_world else client.get_world() + world = client.load_world(town) world.wait_for_tick() - output_dir = os.path.join(output_dir, world.get_map().name[-2:]) - print("Saving images to {}".format(output_dir)) + output_dir = os.path.join(output_dir, town[-2:]) if use_empty_world: ego_vehicle = setup_empty_world(client) diff --git a/code/perception/src/lidar_filter_utility.py b/code/perception/src/lidar_filter_utility.py old mode 100644 new mode 100755 diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py new file mode 100755 index 00000000..84c8d991 --- /dev/null +++ b/code/perception/src/sensor_filter_debug.py @@ -0,0 +1,198 @@ +#!/usr/bin/env python + +""" +This node publishes all relevant topics for the ekf node. +""" +import math +import numpy as np +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from geometry_msgs.msg import PoseStamped +from sensor_msgs.msg import NavSatFix, Imu +from nav_msgs.msg import Odometry +from std_msgs.msg import Float32 +from coordinate_transformation import CoordinateTransformer, GeoRef +from tf.transformations import euler_from_quaternion + +GPS_RUNNING_AVG_ARGS: int = 10 + + +class PositionPublisherNode(CompatibleNode): + """ + Node publishes a filtered gps signal. + This is achieved using a rolling average. + """ + + def __init__(self): + """ + Constructor / Setup + :return: + """ + + super(PositionPublisherNode, self).__init__('ekf_translation') + self.loginfo("Position publisher node started") + + # basic info + self.role_name = self.get_param("role_name", "hero") + self.control_loop_rate = self.get_param("control_loop_rate", "0.05") + + # todo: automatically detect town + self.transformer = CoordinateTransformer(GeoRef.TOWN12) + + # Subscriber + self.imu_subscriber = self.new_subscription( + Imu, + "/carla/" + self.role_name + "/Ideal_IMU", + self.update_imu_data, + qos_profile=1) + + self.gps_subscriber = self.new_subscription( + NavSatFix, + "/carla/" + self.role_name + "/Ideal_GPS", + self.update_gps_data, + qos_profile=1) + + # Publisher + # 2D Odometry (Maybe Speedometer?) + self.ekf_odom_publisher = self.new_publisher( + Odometry, + "/ideal_odom", + qos_profile=1) + + # IMU + self.ekf_imu_publisher = self.new_publisher( + Imu, + "/ideal_imu_data", + qos_profile=1) + + self.avg_xyz = np.zeros((GPS_RUNNING_AVG_ARGS, 3)) + self.avg_gps_counter: int = 0 + # 3D Odometry (GPS) + self.cur_pos_publisher = self.new_publisher( + PoseStamped, + f"/paf/{self.role_name}/ideal_current_pos", + qos_profile=1) + + self.__heading: float = 0 + self.__heading_publisher = self.new_publisher( + Float32, + f"/paf/{self.role_name}/ideal_current_heading", + qos_profile=1) + + def update_imu_data(self, data: Imu): + """ + This method is called when new IMU data is received. + It handles all necessary updates and publishes the heading. + :param data: new IMU measurement + :return: + """ + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + def update_gps_data(self, data: NavSatFix): + """ + This method is called when new GNSS data is received. + The function calculates the average position and then publishes it. + Measurements are also transformed to global xyz-coordinates + :param data: GNSS measurement + :return: + """ + lat = data.latitude + lon = data.longitude + alt = data.altitude + x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + # find reason for discrepancy + x *= 0.998 + y *= 1.003 + + self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) + self.avg_xyz[-1] = np.matrix([x, y, z]) + + avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) + + cur_pos = PoseStamped() + + cur_pos.header.stamp = data.header.stamp + cur_pos.header.frame_id = "global" + + cur_pos.pose.position.x = avg_x + cur_pos.pose.position.y = avg_y + cur_pos.pose.position.z = avg_z + + cur_pos.pose.orientation.x = 0 + cur_pos.pose.orientation.y = 0 + cur_pos.pose.orientation.z = 1 + cur_pos.pose.orientation.w = 0 + + self.cur_pos_publisher.publish(cur_pos) + + def run(self): + """ + Control loop + :return: + """ + self.spin() + + +def main(args=None): + """ + main function + :param args: + :return: + """ + + roscomp.init("position_publisher_node_2", args=args) + try: + node = PositionPublisherNode() + node.run() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() + + +if __name__ == "__main__": + main() From 9c4de0ea7ad0acf03fc846a5e163738be7a2dc2c Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 16:06:35 +0100 Subject: [PATCH 07/14] feat(#78): GPS and IMU debug finished Added error_publisher for both heading_error (IMU Sensor) and location_error (GPS Sensor) --- code/acting/launch/acting.launch | 3 +- code/perception/launch/perception.launch | 3 + code/perception/src/sensor_filter_debug.py | 166 +++++++++++++++++++++ 3 files changed, 171 insertions(+), 1 deletion(-) diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index df4979fb..42ff7b9b 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -55,5 +55,6 @@ - + + diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index e9d99ba2..4244b15f 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -62,4 +62,7 @@ + + + diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 84c8d991..1ae1eed0 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -13,6 +13,11 @@ from std_msgs.msg import Float32 from coordinate_transformation import CoordinateTransformer, GeoRef from tf.transformations import euler_from_quaternion +from std_msgs.msg import Float32MultiArray + +import carla +import rospy +#from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -22,6 +27,7 @@ class PositionPublisherNode(CompatibleNode): Node publishes a filtered gps signal. This is achieved using a rolling average. """ + def __init__(self): """ @@ -30,6 +36,11 @@ def __init__(self): """ super(PositionPublisherNode, self).__init__('ekf_translation') + #self.current_pos = PoseStamped() + self.ideal_corrent_pos = PoseStamped() + self.carla_current_pos = PoseStamped() + self.ideal_imu_data = Imu() + self.loginfo("Position publisher node started") # basic info @@ -79,6 +90,135 @@ def __init__(self): f"/paf/{self.role_name}/ideal_current_heading", qos_profile=1) + # Carla API hero car position + # Get parameters from the launch file + host = rospy.get_param('~host', 'carla-simulator') + port = rospy.get_param('~port', 2000) + timeout = rospy.get_param('~timeout', 100.0) + role_name = rospy.get_param('~role_name', 'hero') + + # Connect to the CARLA server + client = carla.Client(host, port) + client.set_timeout(timeout) + + # Get the world + self.world = client.get_world() + + # Get the ego vehicle + self.vehicle = None + + + # Publish the location + self.carla_pos_publisher = self.new_publisher( + PoseStamped, + f"/paf/{self.role_name}/carla_current_pos", + qos_profile=1) + + # Error Publisher + # publish error distance between current_pos and ideal_corrent_pos & current_pos and carla_current_pos: + # current_pos and ideal_corrent_pos in location_error[0] + # current_pos and carla_current_pos in location_error[1] + self.locoation_error_publisher = self.new_publisher( + Float32MultiArray, + f"/paf/{self.role_name}/location_error", + qos_profile=1) + # Current_pos subscriber: + self.current_pos_subscriber = self.new_subscription( + PoseStamped, + f"/paf/{self.role_name}/current_pos", + self.update_location_error, + qos_profile=1) + + """ + # publish the error between imu and ideal_imu + self.imu_error_publisher = self.new_publisher( + Float32, + f"/paf/{self.role_name}/imu_error", + qos_profile=1) + + # Imu subscriber: + self.imu_subscriber = self.new_subscription( + Imu, + f"/carla/{self.role_name}/IMU", + self.update_imu_error, + qos_profile=1) + """ + """ + def update_imu_error(self, data: Imu): + ""'" + This method is called when new IMU data is received. + It handles all necessary updates and publishes the heading. + :param data: new IMU measurement + :return: + ""'" + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + # calculate the error between ideal_imu and imu + error = Float32() + error.data = math.sqrt((self.ideal_imu_data + """ + + def update_location_error(self, data: PoseStamped): + """ + This method is called when new current_pos data is received. + It handles all necessary updates and publishes the error. + :param data: new current_pos measurement + :return: + """ + + error = Float32MultiArray() + #error.layout.dim = [0, 0] + error.data = [0, 0] + # calculate the error between ideal_current_pos and current_pos + error.data[0] = math.sqrt((self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) + # calculate the error between carla_current_pos and current_pos + error.data[1] = math.sqrt((self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) + self.error_publisher.publish(error) + def update_imu_data(self, data: Imu): """ This method is called when new IMU data is received. @@ -168,6 +308,32 @@ def update_gps_data(self, data: NavSatFix): cur_pos.pose.orientation.w = 0 self.cur_pos_publisher.publish(cur_pos) + self.ideal_current_pos = cur_pos + + # also update carla_car_position: + if self.vehicle is None: + for actor in self.world.get_actors(): + if actor.attributes.get('role_name') == self.role_name: + self.vehicle = actor + break + + + carla_pos = PoseStamped() + carla_pos.header.stamp = data.header.stamp + carla_pos.header.frame_id = "global" + + pos = self.vehicle.get_location() + carla_pos.pose.position.x = pos.x + carla_pos.pose.position.y = -pos.y + carla_pos.pose.position.z = pos.z + + carla_pos.pose.orientation.x = 0 + carla_pos.pose.orientation.y = 0 + carla_pos.pose.orientation.z = 1 + carla_pos.pose.orientation.w = 0 + + self.carla_pos_publisher.publish(carla_pos) + self.carla_current_pos = carla_pos def run(self): """ From d2a24e66edb34dc62d9850e9707e3490cf99b46a Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 16:08:29 +0100 Subject: [PATCH 08/14] feat(#78): GPS and IMU debug finished Added error_publisher for both heading_error (IMU Sensor) and location_error (GPS Sensor) --- code/perception/src/sensor_filter_debug.py | 229 +++++++++------------ 1 file changed, 92 insertions(+), 137 deletions(-) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 1ae1eed0..dbc3c6ff 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -17,7 +17,7 @@ import carla import rospy -#from carla_msgs.msg import CarlaLo +# from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -27,8 +27,6 @@ class PositionPublisherNode(CompatibleNode): Node publishes a filtered gps signal. This is achieved using a rolling average. """ - - def __init__(self): """ Constructor / Setup @@ -36,10 +34,10 @@ def __init__(self): """ super(PositionPublisherNode, self).__init__('ekf_translation') - #self.current_pos = PoseStamped() + # self.current_pos = PoseStamped() self.ideal_corrent_pos = PoseStamped() self.carla_current_pos = PoseStamped() - self.ideal_imu_data = Imu() + self.ideal_heading = Float32() self.loginfo("Position publisher node started") @@ -95,7 +93,6 @@ def __init__(self): host = rospy.get_param('~host', 'carla-simulator') port = rospy.get_param('~port', 2000) timeout = rospy.get_param('~timeout', 100.0) - role_name = rospy.get_param('~role_name', 'hero') # Connect to the CARLA server client = carla.Client(host, port) @@ -107,100 +104,52 @@ def __init__(self): # Get the ego vehicle self.vehicle = None - # Publish the location self.carla_pos_publisher = self.new_publisher( PoseStamped, f"/paf/{self.role_name}/carla_current_pos", qos_profile=1) - - # Error Publisher - # publish error distance between current_pos and ideal_corrent_pos & current_pos and carla_current_pos: - # current_pos and ideal_corrent_pos in location_error[0] - # current_pos and carla_current_pos in location_error[1] - self.locoation_error_publisher = self.new_publisher( + + # Error Publisher + """publish error distance between current_pos and ideal_corrent_pos & + current_pos and carla_current_pos: + # current_pos and ideal_corrent_pos in location_error[0] + # current_pos and carla_current_pos in location_error[1] + """ + self.location_error_publisher = self.new_publisher( Float32MultiArray, f"/paf/{self.role_name}/location_error", qos_profile=1) + # Current_pos subscriber: self.current_pos_subscriber = self.new_subscription( PoseStamped, f"/paf/{self.role_name}/current_pos", self.update_location_error, qos_profile=1) - - """ - # publish the error between imu and ideal_imu - self.imu_error_publisher = self.new_publisher( + + # publish the error between current_heading and ideal_heading + self.heading_error_publisher = self.new_publisher( Float32, - f"/paf/{self.role_name}/imu_error", + f"/paf/{self.role_name}/heading_error", qos_profile=1) - - # Imu subscriber: - self.imu_subscriber = self.new_subscription( - Imu, - f"/carla/{self.role_name}/IMU", - self.update_imu_error, - qos_profile=1) - """ - """ - def update_imu_error(self, data: Imu): - ""'" - This method is called when new IMU data is received. - It handles all necessary updates and publishes the heading. - :param data: new IMU measurement - :return: - ""'" - imu_data = Imu() - - imu_data.header.stamp = data.header.stamp - imu_data.header.frame_id = "hero" - imu_data.orientation.x = data.orientation.x - imu_data.orientation.y = data.orientation.y - imu_data.orientation.z = data.orientation.z - imu_data.orientation.w = data.orientation.w - imu_data.orientation_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.angular_velocity.x = data.angular_velocity.x - imu_data.angular_velocity.y = data.angular_velocity.y - imu_data.angular_velocity.z = data.angular_velocity.z - imu_data.angular_velocity_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.linear_acceleration.x = data.linear_acceleration.x - imu_data.linear_acceleration.y = data.linear_acceleration.y - imu_data.linear_acceleration.z = data.linear_acceleration.z - imu_data.linear_acceleration_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - self.ekf_imu_publisher.publish(imu_data) - - # Calculate the heading based on the orientation given by the IMU - data_orientation_q = [data.orientation.x, - data.orientation.y, - data.orientation.z, - data.orientation.w] + # Current_heading subscriber: + self.current_heading_subscriber = self.new_subscription( + Float32, + f"/paf/{self.role_name}/current_heading", + self.update_heading_error, + qos_profile=1) - roll, pitch, yaw = euler_from_quaternion(data_orientation_q) - raw_heading = math.atan2(roll, pitch) + def update_heading_error(self, data: Float32): + """ + This method is called when new current_heading data is received. + """ + current_heading = data.data - # transform raw_heading so that: - # --------------------------------------------------------------- - # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | - # --------------------------------------------------------------- - heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi - self.__heading = heading - self.__heading_publisher.publish(self.__heading) - # calculate the error between ideal_imu and imu - error = Float32() - error.data = math.sqrt((self.ideal_imu_data - """ + heading_error = self.ideal_heading.data - current_heading + self.heading_error_publisher.publish(heading_error) def update_location_error(self, data: PoseStamped): """ @@ -211,66 +160,18 @@ def update_location_error(self, data: PoseStamped): """ error = Float32MultiArray() - #error.layout.dim = [0, 0] + # error.layout.dim = [0, 0] error.data = [0, 0] # calculate the error between ideal_current_pos and current_pos - error.data[0] = math.sqrt((self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) + error.data[0] = math.sqrt(( + self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 + + (self.ideal_current_pos.pose.position.y - data.pose.position.y)**2) # calculate the error between carla_current_pos and current_pos - error.data[1] = math.sqrt((self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) - self.error_publisher.publish(error) + error.data[1] = math.sqrt(( + self.carla_current_pos.pose.position.x - data.pose.position.x)**2 + + (self.carla_current_pos.pose.position.y - data.pose.position.y)**2) - def update_imu_data(self, data: Imu): - """ - This method is called when new IMU data is received. - It handles all necessary updates and publishes the heading. - :param data: new IMU measurement - :return: - """ - imu_data = Imu() - - imu_data.header.stamp = data.header.stamp - imu_data.header.frame_id = "hero" - - imu_data.orientation.x = data.orientation.x - imu_data.orientation.y = data.orientation.y - imu_data.orientation.z = data.orientation.z - imu_data.orientation.w = data.orientation.w - imu_data.orientation_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.angular_velocity.x = data.angular_velocity.x - imu_data.angular_velocity.y = data.angular_velocity.y - imu_data.angular_velocity.z = data.angular_velocity.z - imu_data.angular_velocity_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - imu_data.linear_acceleration.x = data.linear_acceleration.x - imu_data.linear_acceleration.y = data.linear_acceleration.y - imu_data.linear_acceleration.z = data.linear_acceleration.z - imu_data.linear_acceleration_covariance = [0, 0, 0, - 0, 0, 0, - 0, 0, 0] - - self.ekf_imu_publisher.publish(imu_data) - - # Calculate the heading based on the orientation given by the IMU - data_orientation_q = [data.orientation.x, - data.orientation.y, - data.orientation.z, - data.orientation.w] - - roll, pitch, yaw = euler_from_quaternion(data_orientation_q) - raw_heading = math.atan2(roll, pitch) - - # transform raw_heading so that: - # --------------------------------------------------------------- - # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | - # --------------------------------------------------------------- - heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi - self.__heading = heading - self.__heading_publisher.publish(self.__heading) + self.location_error_publisher.publish(error) def update_gps_data(self, data: NavSatFix): """ @@ -317,7 +218,6 @@ def update_gps_data(self, data: NavSatFix): self.vehicle = actor break - carla_pos = PoseStamped() carla_pos.header.stamp = data.header.stamp carla_pos.header.frame_id = "global" @@ -335,6 +235,61 @@ def update_gps_data(self, data: NavSatFix): self.carla_pos_publisher.publish(carla_pos) self.carla_current_pos = carla_pos + def update_imu_data(self, data: Imu): + """ + This method is called when new IMU data is received. + The function calculates the average position and then publishes it. + :param data: IMU measurement + :return: + """ + imu_data = Imu() + + imu_data.header.stamp = data.header.stamp + imu_data.header.frame_id = "hero" + + imu_data.orientation.x = data.orientation.x + imu_data.orientation.y = data.orientation.y + imu_data.orientation.z = data.orientation.z + imu_data.orientation.w = data.orientation.w + imu_data.orientation_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.angular_velocity.x = data.angular_velocity.x + imu_data.angular_velocity.y = data.angular_velocity.y + imu_data.angular_velocity.z = data.angular_velocity.z + imu_data.angular_velocity_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + imu_data.linear_acceleration.x = data.linear_acceleration.x + imu_data.linear_acceleration.y = data.linear_acceleration.y + imu_data.linear_acceleration.z = data.linear_acceleration.z + imu_data.linear_acceleration_covariance = [0, 0, 0, + 0, 0, 0, + 0, 0, 0] + + self.ekf_imu_publisher.publish(imu_data) + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [data.orientation.x, + data.orientation.y, + data.orientation.z, + data.orientation.w] + + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + self.__heading = heading + self.__heading_publisher.publish(self.__heading) + + self.ideal_heading = Float32(heading) + def run(self): """ Control loop From 8dcc0fd2368a3b652b08521f4a70b21d97c6dfa2 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Sun, 26 Nov 2023 20:09:14 +0100 Subject: [PATCH 09/14] feat(#78): fixed optimal GPS --- code/agent/config/dev_objects.json | 2 +- code/perception/src/sensor_filter_debug.py | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/code/agent/config/dev_objects.json b/code/agent/config/dev_objects.json index 370308aa..90b24361 100644 --- a/code/agent/config/dev_objects.json +++ b/code/agent/config/dev_objects.json @@ -222,7 +222,7 @@ "z": 1.60, "roll": 0.0, "pitch": 0.0, - "yaw": -45.0 + "yaw": 45.0 }, "horizontal_fov": 30.0, "vertical_fov": 30.0, diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index dbc3c6ff..fce6371f 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -35,7 +35,7 @@ def __init__(self): super(PositionPublisherNode, self).__init__('ekf_translation') # self.current_pos = PoseStamped() - self.ideal_corrent_pos = PoseStamped() + self.ideal_current_pos = PoseStamped() self.carla_current_pos = PoseStamped() self.ideal_heading = Float32() @@ -189,19 +189,19 @@ def update_gps_data(self, data: NavSatFix): x *= 0.998 y *= 1.003 - self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) - self.avg_xyz[-1] = np.matrix([x, y, z]) + # self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) + # self.avg_xyz[-1] = np.matrix([x, y, z]) - avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) + # avg_x, avg_y, avg_z = np.mean(self.avg_xyz, axis=0) cur_pos = PoseStamped() cur_pos.header.stamp = data.header.stamp cur_pos.header.frame_id = "global" - cur_pos.pose.position.x = avg_x - cur_pos.pose.position.y = avg_y - cur_pos.pose.position.z = avg_z + cur_pos.pose.position.x = x + cur_pos.pose.position.y = y + cur_pos.pose.position.z = z cur_pos.pose.orientation.x = 0 cur_pos.pose.orientation.y = 0 From 528c5d840fce3db28c78b4652a5b8e4cc1dee68f Mon Sep 17 00:00:00 2001 From: robertik10 Date: Tue, 28 Nov 2023 16:57:48 +0100 Subject: [PATCH 10/14] feat(#78): new coordinate Transformation package --- code/perception/src/sensor_filter_debug.py | 6 +++++- code/requirements.txt | 1 + 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index fce6371f..394789e4 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -17,6 +17,7 @@ import carla import rospy +import pymap3d as pm # from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -184,7 +185,10 @@ def update_gps_data(self, data: NavSatFix): lat = data.latitude lon = data.longitude alt = data.altitude - x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + # x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) + lonref, latref, altref = GeoRef.TOWN12.value + x, y, z = pm.geodetic2enu(lat, lon, alt, + lonref, latref, altref) # find reason for discrepancy x *= 0.998 y *= 1.003 diff --git a/code/requirements.txt b/code/requirements.txt index c15e4287..228a7204 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -11,3 +11,4 @@ scipy==1.10.0 xmltodict==0.13.0 py-trees==2.1.6 numpy==1.23.5 +pymap3d==3.0.0 From dc1b16e20feb3ed34e53ac12230f47bcd973dc53 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Mon, 4 Dec 2023 00:29:04 +0100 Subject: [PATCH 11/14] feat(#78): add kalman filter and sensor filter debug doc(#78): add doc for kalman filter and sensor filter debug bug(#121): fixed bug in pos publishing when starts in dev mode --- build/docker-compose.yml | 2 +- code/acting/launch/acting.launch | 4 +- code/perception/launch/perception.launch | 8 +- .../perception/src/Position_Publisher_Node.py | 6 +- .../src/coordinate_transformation.py | 14 ++- code/perception/src/kalman_filter.py | 89 +++++++++++++++++ code/perception/src/sensor_filter_debug.py | 96 ++++++++++++++++--- 7 files changed, 194 insertions(+), 25 deletions(-) create mode 100644 code/perception/src/kalman_filter.py diff --git a/build/docker-compose.yml b/build/docker-compose.yml index 2f5c93ac..1545f945 100644 --- a/build/docker-compose.yml +++ b/build/docker-compose.yml @@ -58,7 +58,7 @@ services: shm_size: 2gb #command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/opt/leaderboard/leaderboard/autoagents/npc_agent.py --host=carla-simulator --track=SENSORS" command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" - #command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" + #command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" logging: driver: "local" environment: diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index 42ff7b9b..5a90b88a 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -40,10 +40,10 @@ - + - + @@ -63,6 +63,10 @@ - + + + diff --git a/code/perception/src/Position_Publisher_Node.py b/code/perception/src/Position_Publisher_Node.py index 87f03ab9..c52a93b4 100755 --- a/code/perception/src/Position_Publisher_Node.py +++ b/code/perception/src/Position_Publisher_Node.py @@ -175,10 +175,14 @@ def update_gps_data(self, data: NavSatFix): """ # Make sure position is only published when reference values have been # read from the Map - if CoordinateTransformer.ref_set: + if CoordinateTransformer.ref_set is False: + self.transformer = CoordinateTransformer() + CoordinateTransformer.ref_set = True + if CoordinateTransformer.ref_set is True: lat = data.latitude lon = data.longitude alt = data.altitude + x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) diff --git a/code/perception/src/coordinate_transformation.py b/code/perception/src/coordinate_transformation.py index f65dc4cb..203d6988 100755 --- a/code/perception/src/coordinate_transformation.py +++ b/code/perception/src/coordinate_transformation.py @@ -15,15 +15,19 @@ b = 6356752.3142 f = (a - b) / a e_sq = f * (2 - f) +alt_offset = 331.00000 +STD_LAT = 0.0 +STD_LON = 0.0 +STD_H = 0.0 class CoordinateTransformer: """Object that is used to transform Coordinates between xyz and gnss reference frame""" - la_ref: float - ln_ref: float - h_ref: float + la_ref = STD_LAT + ln_ref = STD_LON + h_ref = STD_H ref_set = False def __init__(self): @@ -58,7 +62,9 @@ def geodetic_to_enu(lat, lon, alt): # Is not necessary in new version # y *= -1 - return x, y, alt + 331.00000 + # alt_offset is needed to keep the hight of the map in mind + # right now we don't really use the altitude anyways + return x, y, alt + alt_offset def geodetic_to_ecef(lat, lon, h): diff --git a/code/perception/src/kalman_filter.py b/code/perception/src/kalman_filter.py new file mode 100644 index 00000000..0b5f0fc2 --- /dev/null +++ b/code/perception/src/kalman_filter.py @@ -0,0 +1,89 @@ +import numpy as np +from ros_compatibility.node import CompatibleNode +from geometry_msgs.msg import PoseStamped +from sensor_msgs.msg import Imu +# from std_msgs.msg import Float32 + +''' +This class implements a Kalman filter for a 3D object tracked in 3D space. +It implements the data of the IMU and the GPS Sensors. +The IMU Sensor provides the acceleration +and the GPS Sensor provides the position. +The IMU Data therefore needs to be transformed to Velocity data. + +The Noise for the GPS Sensor is defined as: + "noise_alt_stddev": 0.000005, + "noise_lat_stddev": 0.000005, + "noise_lon_stddev": 0.000005 +The Noise for the IMU Sensor is defined as: + "noise_accel_stddev_x": 0.000, + "noise_accel_stddev_y": 0.000, + "noise_accel_stddev_z": 0.000, + +The state vector x is defined as: + x = [x, y, z, vx, vy, vz] + x: position + v: velocity +The state transition matrix F is defined as: + F = I + I: Identity Matrix +The measurement matrix H is defined as: + H = +The process covariance matrix Q is defined as: + Q = +''' + + +class KalmanFilter(CompatibleNode): + NOISE_ALT_STDDEV = 0.000005 + NOISE_LAT_STDDEV = 0.000005 + NOISE_LON_STDDEV = 0.000005 + + def __init__(self): + # Initialize the state vector x + self.x = np.matrix([0, 0, 0, 0, 0, 0, 0, 0, 0]).T + # Initialize Predected state vector x_hat + self.x_hat = np.matrix([0, 0, 0, 0, 0, 0, 0, 0, 0]).T + # Initialize the state transition matrix F + self.F = np.matrix(np.identity(9)) + # Initialize the measurement matrix H + # self.H = + # Initialize the process covariance matrix Q + self.Q = np.matrix(np.zeros((9, 9))) + # Initialize the measurement covariance matrix R + self.R = np.matrix(np.identity(9)) + # Initialize the covariance matrix P + self.P = np.matrix(np.identity(9)) + # Initialize the predicted covariance matrix P_hat + self.P_hat = np.matrix(np.identity(9)) + # Initialize the acceleration + self.acceleration = np.matrix([0, 0, 0]).T + # Initialize the position + self.position = np.matrix([0, 0, 0]).T + # Initialize the velocity + self.velocity = np.matrix([0, 0, 0]).T + # Initialize the time + self.time = 0 + # Initialize the flag if the filter is initialized + self.initialized = False + + # Subscriber + # Initialize the subscriber for the IMU Data + self.imu_subscriber = self.new_subscription( + Imu, + "/carla/" + self.role_name + "/Ideal_IMU", + self.update_imu_data, + qos_profile=1) + # Initialize the subscriber for the GPS Data + self.gps_subscriber = self.new_subscription( + PoseStamped, + "/carla/" + self.role_name + "/GPS", + self.update_gps_data, + qos_profile=1) + + # Publisher + # Initialize the publisher for the kalman-position + self.kalman_position_publisher = self.new_publisher( + PoseStamped, + "/carla/" + self.role_name + "/Kalman_Position", + qos_profile=1) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 394789e4..11a7800d 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -10,20 +10,20 @@ from geometry_msgs.msg import PoseStamped from sensor_msgs.msg import NavSatFix, Imu from nav_msgs.msg import Odometry -from std_msgs.msg import Float32 -from coordinate_transformation import CoordinateTransformer, GeoRef +from std_msgs.msg import Float32, String +from coordinate_transformation import CoordinateTransformer from tf.transformations import euler_from_quaternion from std_msgs.msg import Float32MultiArray +from xml.etree import ElementTree as eTree import carla import rospy -import pymap3d as pm # from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 -class PositionPublisherNode(CompatibleNode): +class SensorFilterDebugNode(CompatibleNode): """ Node publishes a filtered gps signal. This is achieved using a rolling average. @@ -34,7 +34,7 @@ def __init__(self): :return: """ - super(PositionPublisherNode, self).__init__('ekf_translation') + super(SensorFilterDebugNode, self).__init__('ekf_translation') # self.current_pos = PoseStamped() self.ideal_current_pos = PoseStamped() self.carla_current_pos = PoseStamped() @@ -47,9 +47,15 @@ def __init__(self): self.control_loop_rate = self.get_param("control_loop_rate", "0.05") # todo: automatically detect town - self.transformer = CoordinateTransformer(GeoRef.TOWN12) + self.transformer = None # Subscriber + self.map_sub = self.new_subscription( + String, + "/carla/" + self.role_name + "/OpenDRIVE", + self.get_geoRef, + qos_profile=1) + self.imu_subscriber = self.new_subscription( Imu, "/carla/" + self.role_name + "/Ideal_IMU", @@ -141,6 +147,16 @@ def __init__(self): f"/paf/{self.role_name}/current_heading", self.update_heading_error, qos_profile=1) + + # Publish x and y coordinates of ideal_GPS and carla_pos + self.ideal_x_publisher = self.new_publisher( + Float32MultiArray, + f"/paf/{self.role_name}/ideal_x", + qos_profile=1) + self.ideal_y_publisher = self.new_publisher( + Float32MultiArray, + f"/paf/{self.role_name}/ideal_y", + qos_profile=1) def update_heading_error(self, data: Float32): """ @@ -161,8 +177,8 @@ def update_location_error(self, data: PoseStamped): """ error = Float32MultiArray() - # error.layout.dim = [0, 0] - error.data = [0, 0] + + error.data = [0, 0, 0] # calculate the error between ideal_current_pos and current_pos error.data[0] = math.sqrt(( self.ideal_current_pos.pose.position.x - data.pose.position.x)**2 @@ -174,6 +190,33 @@ def update_location_error(self, data: PoseStamped): self.location_error_publisher.publish(error) + def get_geoRef(self, opendrive: String): + """_summary_ + Reads the reference values for lat and lon from the carla OpenDriveMap + Args: + opendrive (String): OpenDrive Map from carla + """ + root = eTree.fromstring(opendrive.data) + header = root.find("header") + geoRefText = header.find("geoReference").text + + latString = "+lat_0=" + lonString = "+lon_0=" + + indexLat = geoRefText.find(latString) + indexLon = geoRefText.find(lonString) + + indexLatEnd = geoRefText.find(" ", indexLat) + indexLonEnd = geoRefText.find(" ", indexLon) + + latValue = float(geoRefText[indexLat + len(latString):indexLatEnd]) + lonValue = float(geoRefText[indexLon + len(lonString):indexLonEnd]) + + CoordinateTransformer.la_ref = latValue + CoordinateTransformer.ln_ref = lonValue + CoordinateTransformer.ref_set = True + self.transformer = CoordinateTransformer() + def update_gps_data(self, data: NavSatFix): """ This method is called when new GNSS data is received. @@ -185,13 +228,13 @@ def update_gps_data(self, data: NavSatFix): lat = data.latitude lon = data.longitude alt = data.altitude - # x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) - lonref, latref, altref = GeoRef.TOWN12.value - x, y, z = pm.geodetic2enu(lat, lon, alt, - lonref, latref, altref) + + if self.transformer is None: + self.transformer = CoordinateTransformer() + x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) # find reason for discrepancy - x *= 0.998 - y *= 1.003 + # x *= 0.998 + # y *= 1.003 # self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) # self.avg_xyz[-1] = np.matrix([x, y, z]) @@ -239,6 +282,29 @@ def update_gps_data(self, data: NavSatFix): self.carla_pos_publisher.publish(carla_pos) self.carla_current_pos = carla_pos + # get x and y coordinates of ideal_GPS and carla_pos + # publish errors between ideal_x and carla_pos.x + # and ideal_y and carla_pos.y + ideal_x = Float32MultiArray() + ideal_y = Float32MultiArray() + x_error = ( + self.ideal_current_pos.pose.position.x + - self.carla_current_pos.pose.position.x + ) + y_error = ( + self.ideal_current_pos.pose.position.y + - self.carla_current_pos.pose.position.y + ) + ideal_x.data = [self.ideal_current_pos.pose.position.x, + self.carla_current_pos.pose.position.x, + x_error] + ideal_y.data = [self.ideal_current_pos.pose.position.y, + self.carla_current_pos.pose.position.y, + y_error] + + self.ideal_x_publisher.publish(ideal_x) + self.ideal_y_publisher.publish(ideal_y) + def update_imu_data(self, data: Imu): """ This method is called when new IMU data is received. @@ -311,7 +377,7 @@ def main(args=None): roscomp.init("position_publisher_node_2", args=args) try: - node = PositionPublisherNode() + node = SensorFilterDebugNode() node.run() except KeyboardInterrupt: pass From 8dcf9f74e3bb4acb422524b6eac28a5d86b259be Mon Sep 17 00:00:00 2001 From: robertik10 Date: Mon, 4 Dec 2023 00:32:08 +0100 Subject: [PATCH 12/14] feat(#78): add kalman filter and sensor filter debug doc(#78): add doc for kalman filter and sensor filter debug bug(#121): fixed bug in pos publishing when starts in dev mode --- code/perception/launch/perception.launch | 24 +- .../perception/src/Position_Publisher_Node.py | 2 +- code/perception/src/kalman_filter.py | 352 +++++++++++++++--- code/perception/src/sensor_filter_debug.py | 72 ++-- doc/00_assets/gnss_ohne_rolling_average.png | Bin 0 -> 227082 bytes doc/06_perception/10_sensor_filter_debug.md | 147 ++++++++ doc/06_perception/11_kalman_filter.md | 144 +++++++ doc/06_perception/Readme.md | 4 + 8 files changed, 656 insertions(+), 89 deletions(-) mode change 100644 => 100755 code/perception/src/kalman_filter.py create mode 100644 doc/00_assets/gnss_ohne_rolling_average.png create mode 100644 doc/06_perception/10_sensor_filter_debug.md create mode 100644 doc/06_perception/11_kalman_filter.md diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index da2eed34..0a24ba5e 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -3,16 +3,32 @@ - + + + + + @@ -63,10 +79,4 @@ - - - - diff --git a/code/perception/src/Position_Publisher_Node.py b/code/perception/src/Position_Publisher_Node.py index c52a93b4..8c0431c2 100755 --- a/code/perception/src/Position_Publisher_Node.py +++ b/code/perception/src/Position_Publisher_Node.py @@ -182,7 +182,7 @@ def update_gps_data(self, data: NavSatFix): lat = data.latitude lon = data.longitude alt = data.altitude - + x, y, z = self.transformer.gnss_to_xyz(lat, lon, alt) self.avg_xyz = np.roll(self.avg_xyz, -1, axis=0) diff --git a/code/perception/src/kalman_filter.py b/code/perception/src/kalman_filter.py old mode 100644 new mode 100755 index 0b5f0fc2..cc8c175a --- a/code/perception/src/kalman_filter.py +++ b/code/perception/src/kalman_filter.py @@ -1,71 +1,145 @@ +#!/usr/bin/env python + import numpy as np +import ros_compatibility as roscomp from ros_compatibility.node import CompatibleNode from geometry_msgs.msg import PoseStamped -from sensor_msgs.msg import Imu -# from std_msgs.msg import Float32 +from std_msgs.msg import Float32, UInt32 +from sensor_msgs.msg import NavSatFix, Imu +from tf.transformations import euler_from_quaternion +from carla_msgs.msg import CarlaSpeedometer +import math ''' This class implements a Kalman filter for a 3D object tracked in 3D space. It implements the data of the IMU and the GPS Sensors. The IMU Sensor provides the acceleration and the GPS Sensor provides the position. -The IMU Data therefore needs to be transformed to Velocity data. +The Carla Speedometer provides the current Speed in the headed direction. The Noise for the GPS Sensor is defined as: "noise_alt_stddev": 0.000005, "noise_lat_stddev": 0.000005, "noise_lon_stddev": 0.000005 The Noise for the IMU Sensor is defined as: - "noise_accel_stddev_x": 0.000, - "noise_accel_stddev_y": 0.000, - "noise_accel_stddev_z": 0.000, - -The state vector x is defined as: - x = [x, y, z, vx, vy, vz] - x: position - v: velocity + "noise_accel_stddev_x": 0.001, + "noise_accel_stddev_y": 0.001, + "noise_accel_stddev_z": 0.015, + +The state vector X is defined as: + [initial_x], + [initial_y], + [yaw], + [v_hy] in direction of heading hy, + [a_hy] in direction of v_hy (heading hy), + [omega_z], The state transition matrix F is defined as: - F = I + A = I I: Identity Matrix The measurement matrix H is defined as: - H = + H = [1, 0, 0, 0, 0, 0], + [0, 1, 0, 0, 0, 0], + [0, 0, 1, 0, 0, 0], + [0, 0, 0, 0, 0, 1] The process covariance matrix Q is defined as: - Q = + Q = np.diag([0.005, 0.005, 0.001, 0.0001] ''' class KalmanFilter(CompatibleNode): - NOISE_ALT_STDDEV = 0.000005 - NOISE_LAT_STDDEV = 0.000005 - NOISE_LON_STDDEV = 0.000005 - + """ + This class implements a Kalman filter for a 3D object tracked in 3D space. + """ def __init__(self): - # Initialize the state vector x - self.x = np.matrix([0, 0, 0, 0, 0, 0, 0, 0, 0]).T - # Initialize Predected state vector x_hat - self.x_hat = np.matrix([0, 0, 0, 0, 0, 0, 0, 0, 0]).T - # Initialize the state transition matrix F - self.F = np.matrix(np.identity(9)) - # Initialize the measurement matrix H - # self.H = - # Initialize the process covariance matrix Q - self.Q = np.matrix(np.zeros((9, 9))) - # Initialize the measurement covariance matrix R - self.R = np.matrix(np.identity(9)) - # Initialize the covariance matrix P - self.P = np.matrix(np.identity(9)) - # Initialize the predicted covariance matrix P_hat - self.P_hat = np.matrix(np.identity(9)) - # Initialize the acceleration - self.acceleration = np.matrix([0, 0, 0]).T - # Initialize the position - self.position = np.matrix([0, 0, 0]).T - # Initialize the velocity - self.velocity = np.matrix([0, 0, 0]).T - # Initialize the time - self.time = 0 - # Initialize the flag if the filter is initialized - self.initialized = False + """ + Constructor / Setup + :return: + """ + + super(KalmanFilter, self).__init__('kalman_filter_node') + + self.loginfo('KalmanFilter node started') + # basic info + self.role_name = self.get_param("role_name", "hero") + self.control_loop_rate = self.get_param("control_loop_rate", "0.001") + self.publish_seq = UInt32(0) + self.frame_id = "map" + + self.dt = self.control_loop_rate + + # Initialize the state vector X + ''' + [ + [initial_x], + [initial_y], + [yaw], + [v_hy] in direction of heading hy, + [a_hy] in direction of v_hy (heading hy), + [omega_z], + ] + ''' + self.x0 = np.zeros((6, 1)) + + # Define initial state covariance matrix + self.P0 = np.eye(6) + + # Define state transition matrix + # [x, y, yaw, v_hy, a_hy, omega_z] + # [ ... ] + self.A = np.array([[1, 0, 0, self.dt, 0, 0], + [0, 1, 0, 0, self.dt, 0], + [0, 0, 1, 0, 0, self.dt], + [0, 0, 0, 1, 0, 0], + [0, 0, 0, 0, 1, 0], + [0, 0, 0, 0, 0, 1]]) + + # Define measurement matrix + ''' + 1. GPS: x, y + 2. IMU: yaw, omega_z + -> 4 measurements for a state vector of 6 + (v is not in the measurement here because its provided by Carla) + ''' + self.H = np.array([[1, 0, 0, 0, 0, 0], + [0, 1, 0, 0, 0, 0], + [0, 0, 1, 0, 0, 0], + [0, 0, 0, 0, 0, 1]]) + + # Define process noise covariance matrix + self.Q = np.diag([0.0001, 0.0001, 0.0001, 0.0001, 0.0001, 0.0001]) + + # Define measurement noise covariance matrix + self.R = np.diag([0.005, 0.005, 0.001, 0.0001]) + + # Define Measurement Variables + self.z_gps = np.zeros((2, 1)) # GPS measurements (x, y) + self.z_imu = np.zeros((2, 1)) # IMU measurements (yaw, omega_z) + + self.v = np.zeros((2, 1)) # Velocity measurements (v_x, v_y) + + self.x_old_est = np.copy(self.x0) # old state vector + self.P_old_est = np.copy(self.P0) # old state covariance matrix + self.x_est = np.zeros((6, 1)) # estimated state vector + self.P_est = np.zeros((6, 6)) # estiamted state covariance matrix + self.x_pred = np.zeros((6, 1)) # Predicted state vector + self.P_pred = np.zeros((6, 6)) # Predicted state covariance matrix + + self.K = np.zeros((6, 4)) # Kalman gain + + self.latitude = 0 # latitude of the current position + + ''' + # Define control input vector + u = np.array([0, 0, -g, 0, 0, 0]) + + # Define control input matrix + B = np.array([[0, 0, 0], + [0, 0, 0], + [0, 0, 0], + [0, 0, dt], + [0, dt, 0], + [dt, 0, 0]]) + ''' # Subscriber # Initialize the subscriber for the IMU Data @@ -76,14 +150,200 @@ def __init__(self): qos_profile=1) # Initialize the subscriber for the GPS Data self.gps_subscriber = self.new_subscription( - PoseStamped, + NavSatFix, "/carla/" + self.role_name + "/GPS", self.update_gps_data, qos_profile=1) + # Initialize the subscriber for the current_pos in XYZ + self.current_pos_subscriber = self.new_subscription( + PoseStamped, + "/paf/" + self.role_name + "/current_pos", + self.update_current_pos, + qos_profile=1) + # Initialize the subscriber for the velocity + self.velocity_subscriber = self.new_subscription( + CarlaSpeedometer, + "/carla/" + self.role_name + "/Speed", + self.update_velocity, + qos_profile=1) # Publisher # Initialize the publisher for the kalman-position self.kalman_position_publisher = self.new_publisher( PoseStamped, - "/carla/" + self.role_name + "/Kalman_Position", + "/paf/" + self.role_name + "/kalman_pos", qos_profile=1) + self.kalman_heading_publisher = self.new_publisher( + Float32, + "/paf/" + self.role_name + "/kalman_heading", + qos_profile=1) + + def run(self): + """ + Run the Kalman Filter + """ + def loop(): + """ + Loop for the Kalman Filter + """ + self.predict() + self.update() + + # Publish the kalman-data: + self.publish_kalman_heading() + self.publish_kalman_location() + + # roscomp.spin(loop, self.control_loop_rate) + self.new_timer(self.control_loop_rate, loop) + self.spin() + + def predict(self): + """ + Predict the next state + """ + # Update the old state and covariance matrix + self.x_old_est[:, :] = np.copy(self.x_est[:, :]) + self.P_old_est[:, :] = np.copy(self.P_est[:, :]) + + # Predict the next state and covariance matrix + self.x_pred = self.A @ self.x_est[:] # + B @ v[:, k-1] + u + self.P_pred = self.A @ self.P_est[:, :] @ self.A.T + self.Q + + def update(self): + """ + Update the state + """ + z = np.concatenate((self.z_gps[:], self.z_imu[:])) # Measurementvector + y = z - self.H @ self.x_pred # Measurement residual + S = self.H @ self.P_pred @ self.H.T + self.R # Residual covariance + self.K[:, :] = self.P_pred @ self.H.T @ np.linalg.inv(S) # Kalman gain + self.x_est[:] = self.x_pred + self.K[:, :] @ y # State estimate + # State covariance estimate + self.P_est[:, :] = (np.eye(6) - self.K[:, :] @ self.H) @ self.P_pred + + def publish_kalman_heading(self): + """ + Publish the kalman heading + """ + # Initialize the kalman-heading + kalman_heading = Float32() + + # Fill the kalman-heading + kalman_heading.data = self.x_est[2] + + # Publish the kalman-heading + self.kalman_heading_publisher.publish(kalman_heading) + + def publish_kalman_location(self): + """ + Publish the kalman location + """ + # Initialize the kalman-position + kalman_position = PoseStamped() + + # Fill the kalman-position + kalman_position.header.frame_id = self.frame_id + kalman_position.header.stamp = roscomp.Time.now() + kalman_position.header.seq = self.publish_seq + self.publish_seq.data += 1 + + kalman_position.pose.position.x = self.x_est[0] + kalman_position.pose.position.y = self.x_est[1] + kalman_position.pose.position.z = self.latitude + kalman_position.pose.orientation.x = 0 + kalman_position.pose.orientation.y = 0 + kalman_position.pose.orientation.z = 1 + kalman_position.pose.orientation.w = 0 + + # Publish the kalman-position + self.kalman_position_publisher.publish(kalman_position) + + def update_imu_data(self, imu_data): + """ + Update the IMU Data + """ + orientation_x = imu_data.orientation.x + orientation_y = imu_data.orientation.y + orientation_z = imu_data.orientation.z + orientation_w = imu_data.orientation.w + + # Calculate the heading based on the orientation given by the IMU + data_orientation_q = [orientation_x, + orientation_y, + orientation_z, + orientation_w] + + # Implementation by paf22 in Position_Publisher_Node.py + # TODO: Why were they using roll and pitch instead of yaw? + # Even though they are basically deriving the yaw that way? + roll, pitch, yaw = euler_from_quaternion(data_orientation_q) + raw_heading = math.atan2(roll, pitch) + + # transform raw_heading so that: + # --------------------------------------------------------------- + # | 0 = x-axis | pi/2 = y-axis | pi = -x-axis | -pi/2 = -y-axis | + # --------------------------------------------------------------- + heading = (raw_heading - (math.pi / 2)) % (2 * math.pi) - math.pi + + # update IMU Measurements: + self.z_imu[0] = heading + self.z_imu[1] = imu_data.angular_velocity.z + if imu_data.orientation_covariance[8] != 0: + # [8] because we want the diag z element of the covariance matrix + self.R[2, 2] = imu_data.orientation_covariance[8] + if imu_data.angular_velocity_covariance[8] != 0: + # [8] because we want the diag z element of the covariance matrix + self.R[3, 3] = imu_data.angular_velocity_covariance[8] + + def update_gps_data(self, gps_data): + """ + Update the GPS Data + Currently only used for covariance matrix + """ + # look up if covariance type is not 0 (0 = COVARANCE_TYPE_UNKNOWN) + # (1 = approximated, 2 = diagonal known or 3 = known) + # if it is not 0 -> update the covariance matrix + if gps_data.position_covariance_type != 0: + # [0] because we want the diag lat element of the covariance matrix + self.R[0, 0] = gps_data.pose.covariance[0] + # [5] because we want the diag lon element of the covariance matrix + self.R[1, 1] = gps_data.pose.covariance[5] + pass + + def update_current_pos(self, current_pos): + """ + Update the current position + """ + # update GPS Measurements: + self.z_gps[0] = current_pos.pose.position.x + self.z_gps[1] = current_pos.pose.position.y + + self.latitude = current_pos.pose.position.z + + def update_velocity(self, velocity): + """ + Update the velocity using the yaw angle in the predicted state x1 + x1[2] = yaw + """ + self.v[0] = velocity.speed * math.cos(self.x_est[2]) + self.v[1] = velocity.speed * math.sin(self.x_est[2]) + + +def main(args=None): + """ + Main function starts the node + :param args: + """ + roscomp.init('kalman_filter_node', args=args) + + try: + node = KalmanFilter() + node.run() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() + + +if __name__ == '__main__': + main() diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index 11a7800d..b1c92b79 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -49,13 +49,29 @@ def __init__(self): # todo: automatically detect town self.transformer = None - # Subscriber + # Carla API hero car position + # Get parameters from the launch file + host = rospy.get_param('~host', 'carla-simulator') + port = rospy.get_param('~port', 2000) + timeout = rospy.get_param('~timeout', 100.0) + + # Connect to the CARLA server + client = carla.Client(host, port) + client.set_timeout(timeout) + + # Get the world + self.world = client.get_world() + + # Get the ego vehicle + self.vehicle = None + + # Subscriber START self.map_sub = self.new_subscription( String, "/carla/" + self.role_name + "/OpenDRIVE", self.get_geoRef, qos_profile=1) - + self.imu_subscriber = self.new_subscription( Imu, "/carla/" + self.role_name + "/Ideal_IMU", @@ -68,7 +84,22 @@ def __init__(self): self.update_gps_data, qos_profile=1) - # Publisher + # Current_pos subscriber: + self.current_pos_subscriber = self.new_subscription( + PoseStamped, + f"/paf/{self.role_name}/current_pos", + self.update_location_error, + qos_profile=1) + + # Current_heading subscriber: + self.current_heading_subscriber = self.new_subscription( + Float32, + f"/paf/{self.role_name}/current_heading", + self.update_heading_error, + qos_profile=1) + # Subscriber END + + # Publisher START # 2D Odometry (Maybe Speedometer?) self.ekf_odom_publisher = self.new_publisher( Odometry, @@ -95,23 +126,7 @@ def __init__(self): f"/paf/{self.role_name}/ideal_current_heading", qos_profile=1) - # Carla API hero car position - # Get parameters from the launch file - host = rospy.get_param('~host', 'carla-simulator') - port = rospy.get_param('~port', 2000) - timeout = rospy.get_param('~timeout', 100.0) - - # Connect to the CARLA server - client = carla.Client(host, port) - client.set_timeout(timeout) - - # Get the world - self.world = client.get_world() - - # Get the ego vehicle - self.vehicle = None - - # Publish the location + # Publish the carla location self.carla_pos_publisher = self.new_publisher( PoseStamped, f"/paf/{self.role_name}/carla_current_pos", @@ -128,26 +143,12 @@ def __init__(self): f"/paf/{self.role_name}/location_error", qos_profile=1) - # Current_pos subscriber: - self.current_pos_subscriber = self.new_subscription( - PoseStamped, - f"/paf/{self.role_name}/current_pos", - self.update_location_error, - qos_profile=1) - # publish the error between current_heading and ideal_heading self.heading_error_publisher = self.new_publisher( Float32, f"/paf/{self.role_name}/heading_error", qos_profile=1) - # Current_heading subscriber: - self.current_heading_subscriber = self.new_subscription( - Float32, - f"/paf/{self.role_name}/current_heading", - self.update_heading_error, - qos_profile=1) - # Publish x and y coordinates of ideal_GPS and carla_pos self.ideal_x_publisher = self.new_publisher( Float32MultiArray, @@ -157,6 +158,7 @@ def __init__(self): Float32MultiArray, f"/paf/{self.role_name}/ideal_y", qos_profile=1) + # Publisher END def update_heading_error(self, data: Float32): """ @@ -177,7 +179,7 @@ def update_location_error(self, data: PoseStamped): """ error = Float32MultiArray() - + error.data = [0, 0, 0] # calculate the error between ideal_current_pos and current_pos error.data[0] = math.sqrt(( diff --git a/doc/00_assets/gnss_ohne_rolling_average.png b/doc/00_assets/gnss_ohne_rolling_average.png new file mode 100644 index 0000000000000000000000000000000000000000..68fb5ebf690725d59f31fb720611b72927240b4c GIT binary patch literal 227082 zcmeFZXHZmY*DczJf^Gy1TTqao5>y1Xk_05URiHsYiIPRK(4b9{j3Qzp2$GWlL~?E< zBL*^PlWBrT0}@-Z&~*2i3q{}io%@}-f6l#itIn=^>lJ9$de-yIIp!E+&c%aE8p_On zar}isp_tJs=e1C%9rY;G*1qiw@EwQq>@o0vTb=(!>uiVrytiB4hp!K~T)5(*?PTrZ zZjQA=**H33tc0B{uvS)%&bCf2B>HN36p9yxK7Ur{R>JgvUCh(YM5!-kQkgv`9u{oJ zyuW$j#a0Q1^ZYwhjZqT%mqyed=izwohT63(e7V~&hSkdPguy+{xH|n=G=JQ-rk-b z*7);3{#O+}+cv*I)kN{~GH!mQh~5+S`-9K;cGS~t{^U~lR^sNrQAg2Ru)n`}%10;t z`wP`@|AW83;72R6Y<}S%&iDW9HgRm_{vV&cdL`ggF{fl$;+R-aP;f2!_o8Z)UT0^w zn9mLW3q2{2 zrXDYOA%~&IP%rDs6Z_ms$#?gd)gG}4KQv*$jdeVJ#?z<#8MI7H61m*_PYUT}sbDaefF(kf zL7})EKIQG&<_2AD-(HXL@9XQUSRIRBZ8D>3O>6lx=olHrzhhN6lUq&oY;0`gC?dJd z^rdR2X)q6pZf+Q-hN2^V7E7J$w@-(%4U6~Oy1nPJwsr)+T9jq9i5uF(<6XjO6Sxkm z!umf>)fBhz6zB0)X8fPu*HoMp%Q7s^*cDC^yFK>Bc8hX^?k8?VU^d1ygF_#V%b!VklTTY?p!mG zH(%~ti~ekj$zJtX>eO#fK}Wbu;Q1>(m-=4g&IPfk8yFb8BnNNq=cQ!-ez&XNK0QAm z?|my^Ny?A9{`jEuDXGC*7Hp!X2^OJpxEoGzTj`|^ZBB=*7754xH{KI!X2%XCliT;lu*+<}ba8PpbJtMcn8&$b9tC;UGv5^}?cE1G zY|7k8No>M~DPAkHrR3T2sex+h+En4Kxv%OuoAK?ReNHjweP>4pG0AJT;mg|q&aAdT zCUyZd11ooeMxspWg-2|GUb?!v%raeRy88M~9ScTfN$U9vt+Hv53Liu)Dv|w`$bq9i zE+HWiKVSwQW?<%c3i+mSY^Rkt$a-VC9u-V=eK~BO$UP`}XZaVgT0YWYrMPA4sOG zEj5*nC∈yJrQF-0)eMCy~#f$o4X_RSzFNgv=E@|QEO`o2hV@jTgP`+P9qmrdZ9*Y&UYsjYRX6i{V_gE}^eI&{@8_FpqGSgSw zL|GY1hW{zR`d9n9t8kZPV}iM4CCQ{}KSP{DEM=J>D%F4E-0^rK`7vLkr#TkMWEJcmHJmXxuL-6m~#3|#jh*|zZZqAJj}HIvh`pQ14t9RD z{z&M>a<`ekx|Ko>#vVF%k2sN*+RZqDm&TsH zdCk;gH1glmnFR%>klYO?2C|#hfBo=iY8$hH9RNq{NeiWnjEwm@1?ovicnw0(7L|5;M}RJKU&Zv z(v)2?Xh5St=civp)s5 zI73-%Kk(00MaXR((TbGtYB0U!4+0C$Xe;Cv!?|?DR&HVrP z(k`E=N6+Vn`TY8Vk$W>`S5{yjrLdSYRU3G;e50O1zH5ug^LNNPY(U~C>7qpb$Ja6^(ns3gt9%F$TX7&0_so% z-%I7tR#^Vishn~V1=?y`H(?0s+^MTI{s?3=MF}?vm-L65Q6}{R6X~2Pm%3aa?M>s= z6URHN=Qx#hZ~&77)Mt!3P%uaFGuLbw*j;+=8|nK#RDaD;!qfG2g8 z_$8oZHb%@wpwbibV_{*ut!*l|I*Cdlcb5;AyOV0kP!Yz$&apH=Kr?kCAUOsXYE1^r zTAy+9Q*(87^<17V9n6msF^N;=_TZBmaM7-uf+W2Bs%~@AZkL?Zyjj!}tDYEYtL00fQh&v9r(E4&ob<2;rk#1?J z}r7C$F7{fR9)i^vcZ>>wR(I5pn@n9NC2nxMGWW5SQMYt|}k$ zbUCSNsVV|W&c524XaqWI&*ZehQAZ#&(alJlat2z>;@}5DoHmc z@Tndn!BW^C!$I9%vyfkH{iV(dh1KW?fzf2zYH~z}PhDqc=aO$I5;w~O?n9m!N!KKH z5#yL9k@6FoXXegFoiG4^THAs}PjYc3bj+OoF=4;C{o=k`u<^Fll*ujjMqbUqmvwa` zUxv!d$WG_Ivym^CSr;>}y=#1HI1q^>Je)(33<-OOkY;FCd#r8lHQDjEX`&MWi2*LwWn!n!f~xF&y;t0 zN~MG@wGie_%>X3yz#ZqkTwCMR=7Fgs}~ z-mxs*bh{`zPTWq5MAB??){$`lf=k!Fa~m_ z-=$r>7gI8z1;mtF&ePkv9ExvtzEMBa?-x*ydrI;im$f(c z1N6rdpD05aLOZ~rORw}hNAN+#w_RJD(C!%(N+&$9KlhPC-1d`FXLqK4ZokKPVlQw! ze9^=`+TXByNkFSci@QyQrcqK(gB9N2-!k_4(I`wy2mRLP?C;h{z6zyhJ@XHsWsAc4 zJB6&z)Yb9iws3y6Q`b9Q|4Rn=>+pKzu`q@X2M&n3Sjf#xw=MV>uF zTVIeKPjH^6l1bx$i5Iol4dbBX%~sQ>C$8l20^>4B@|;Xx3Mq!{=!d5~aOT!`rOsQe z(&I#=65FLEZa_Ekuuy@pW3e_lQaWALezb$PzTB3E>Lq61m31*$UJjuxAu^M%Yx9$! zluTvYoLhUdKHs!3Wk!>UHuLouYfDbHN%9atz&(Nw*?>4Hr=(=cw2jB=XtXwDhEQ%r z!QlR6a{ss%@KJ;`!2!D$IP?}sO!jz@D#dPn|Khz;KGXtd9t9~rMxs$k?Wttx3n@^s+=85i5eCYqB$Ux&vaYy=*FX1&{wqHpRsk-AP@scy?N ze<%5EA<>Vz8hgr0RVkD^aXi^i9>MnjR{0nvkvCV5Snv2F5DS6r zq!WyU975zFSgmUO=_WqERBlzEts@v`sxsOBOJ_|(9hRQ2Khh3oHVsU>6li#O$IPu2 zyqYNTYw`Wc;fqtt~p4C@-dyH`VnG+3z(VieBIJ=j85s?)t{ArWCf2c#U0 z<)Pw@zkV6g_~zyaKHI27eGtz0zy{g+cf9NUmg1b9 zF$b8SmZ%_Qz(){|4TVU?zn3Rvf$qTz3@c#G0g$od~Cex?7u7CgX z79NVER4fgFuYLJ)e&F#fzc%REb8%reI)?+v{nCzV(`XSB+%1 zJ-P*(7fb;C`Osu@#VB#r(GMbYJOloZK5mVA;tfBM!Oalt)ES@yQY8v5%Zi%^*vhr}OLBW`p6jKEurHHr!8{}5{Bi;ruN?l0??R7DH zC-<4ti88LLKo>LE*27J~I@%a8QUxqb3=8!lJS2nbdhlI;n;NDzGFtU<( zNsM7*QKww)5Oozu zKBDxvzUDT41mEcB=+eI$5JZMaKFhtHvW>z91$=^uE?S1g*CV0A$wIMOnv9onG6fd< z26$_VMP0~hS4mYQcx!*pt^hJ3f(TJsCT_j_$~-Qd=OiI$PQc;2dG4hFtiXl zy)xwIw>;!WgY^?ZW%Vh|T$Oa2?wN)%j~F`3z`*)%ykidZ%JgI3D{xVz+LwZ?sUJ*{ zz?*(hQ&YjsvV+I^-{4Vvdmc14nVH*~o|a@Ny1rQsYjDb7k-`30eW|&PIK{bZ;c6lc zNErY*k2p~W#BDDPg5kvHD% zrAW}R9ps%QgP!(?D+>5O3Q2hpoLr4FbMGrafxu;z=WFO$Er)9Z5zB3|I9|r}I&y;a zET^vqd-R6MgThZr0PZdg?wy#|^7O?-841LR8ukT7o>MX3*qkUUwO3H18Muztb{h~y zW395Ji{TaDYncoxZr!YWHY~^t;2>t*tO9#O1&iSo4kua1?3P>E5{`mT+yKg9M0Lb_1=TP6LJhUHmu?l{^Ic1X>#%{e~2BdWOG0QW`XU!{eQ*q`^rsmH}J^K`7sC?5qw>O+;F zn|@T@j2+^g8}RtX06p#Ea;~O?>t#!3py7ex-rA%-#1G8%qfDX0&DOuNBeoGDdcA4n zAx#h-r?ABO+Cs#U90^rOf*^nsK9v6Y_0g?gZUu$>TpC=`a6Ww#S6$!b z!elE@5r}mcg$ z-@0YiHe&&4ARvf|4C03{l;NOM!bn8)Wgw ztg9Tp$2sXUd(z?~kx}8tSq-_R4!(wOpIKVEg{5UF=u?1O#S0{-8Gr!` z76ehhdQI2drUr6D0!nyxx3%`T$C8tGv5{jbKbMRPl8ks@Tg-8?o8XPZfZUy29ghfL z9W1kGO^98bEPfl>maL$F^fuO3NMm#Ov|P&J0m%`#0x)d>&aTO6Zf8)59sn;|z*m&~pkSTYN|Z0P zCrq~KLdDpQ<43Q|4zvT~X@(U9aeLZ=$G8CdBMFSqY`ouFj|Z;M;9gB0aP=KSOhjlE z#ERKy3<6cFZMB4=rwSM7?wxIS702|62XVPw88!s_wGec97g+-;i0<|}euU33ExeHj z8mnRIHB*eph$Z=^#z-NAOM15XdL~7rfT~=odIz+53|yjmsN|-kQl#etjybReV)(V%tzJ51ZZWcIkFUYZ}V#MlubHiK&BqZR_UV{Qlbfw#$4j+M$u2j8v$k+9D zakku;(rXAM#6stC>lqeH78Vjx3rE~rkUZu{tRPwxICm=))kH*LRL+n;T zq);Y2G$zNcVip!B?Cs;*G*?!@f3oh%GC-h|2_xS$*1P}(UE9DQ7Tk$ri1q=Zfy7_% zn(t=(_272YV=@3tu1l3%ivckOx`UK;lkz|?ss4#FcWjEIU_Ko17-Xe-I3l>fmDDtk z&V}#iFdwi7X3wc>mTOvx1*EhF@vYMSij%564f-3r`lrC;v-9Ztks9=tk;jroSrP4U z2HKOmdkY~(o(23$1nz0yS!sDnWJCxeosid;U;Z^?(;Rb|6bqiZAR5Yd@!*CRbq2^l z;1RtcKv4jnXP4^6zJW?9bD0PSxhxF`yk@=94fFzOrFsA_{Hyvop9kD-;e)8}%}PvW zMh4;-A+!QL8PbY@txCG}^}#f#esnnS0R^xt>Jj(dvVD9Ncu@;tRU-g#|44{R_!*#s z@e7|fF}a5!lD!;-dkp;wSxvbm9gWk&cO_;i>*ES-@T(iD7F-04L2y$NJjPUE`?&+?=jEw7*OF*I!_rRAjWi~$FB-#c~0m#}$OjDrP zg%m^&GH}FSW zE`Ixr$jSLyCQ-{D--i+KKqUAQj=bm&sPqKsogv+pR~m_N&>oXSTA0v+5mtjrDLYf7 z-B;q240MLps3uzZbcjY>IUwl(j!)I(rf0&WS8(g0^1jll#z9KsV05+s^045%BeW6X0fWu4$rpRXlCq=3f!a|`# za|#q|8?-B80g#WN2SVIMD;Krk*YX;C_|QNw=b`N;05u(u+@@+iGWYM0IA~Xyhyi6? zACsy^uvrX5EfAVlgZoX&TpAFz=KbTl3%E9UYC~yAe+|}k1Bpchw*YxcA(pyN>$z(C zjLQx+v`7sl+#LBhx{yrsMx3X|(5r(=NJybVg{?4l`Fx@D+lxo@t8ISr!10hi~qeuYawT7ITuScW`JdP&7*%T!N4Bn=uCNbajA3$rw zeu⪙)$sDFw<%+dsP^;!XUR#BLB|o8rZ*?PPY9UQyq^?&gTo8l!=2O(*jQtCW-0m zC|?11h7dJHmpBd}9Q?5En>nPj3+B=od5Gpa+y^&`a~vqM0{E5aCR5&;| zad(8sO3Y$1?HTiyvajSHM*N)b!|&R`R)--DhoJwk5`KFN`36Bf##4>{y=QaIFF^+~ zEzzw{??9$o8{vCYX>%%^MB6M&x!l7U9q4sohQbv(}R~R7#(wqC{3&#ma%2pYY z>jd6PNUs262k{M-U@oHczzF8-M8*n`++oYu`D=Cl_YU(i65c>3Dzk@wbH$1;bxfy! z8w{wcYH$lhXw82Rq3gMK<+qT2*tR<}`8ia3g!m$%f_P{x@lu*VNb;Mua45pi1%i=C zBYSj|If6YWJ6j!698Ng#X>@cN{N{h1+CaW-RN{!pgF$eH;iSZ$LE8i|sSI!q1_6v_ zpt>UgrYqmxao=37!x_3#=1)+nka}QHinW5eqdSfLIi&(9C^ZC54u?xx2~dv|&^m7M zTYvrP(Npl7I$*#8BBvS@T7MAPX3GmQ9?2TRBHJfW3I8ttJx0V4Q%Kvq=l|BpqyLu% zoc_;k{@aPC|Idfd{?FO`|Kx0fMR-?`sR=|tIF`>u!O#-)({Bb4G+@>P`nKwANpdAu z1ApU&0~3ddqT}lPsPwmI0rN=Pm9ujeIwfYc()*ig z3dGMamp&Drrnvoio)DxKAf@;hMff|%sa>`nnfw|8o+Jit z2QnGK**^=meG6DCfBA_5r-+P<1g?0cvVl&O0PTT!q!(5S)p4_!r)6DGgxc-@vBnVT z3v9RD`Rg0k3R&_?kuLt_mrB_;ed1Z_DNDJ2EkMIgfnk*Z<0t5FXfStlb-jYRfUtFh zyk&jPf##|`C8#K8O3`k?iRbtA{%>!P-nCTT`-&b5W0(zMZD+vKVV3F-LkRBb5I8R2 z*Ji6k{y8THh?o-S^HnV3)dH){py7hBU!>#i21LLZ+HI>q@)8j93F@jQj6F;ilfXcM z(W}yru79>t6s{v>@$s=Y%rA(n%Q^Jq@il;-FoQ6|N9>}lKy)7JZdlDVxTzMYDN|Y3 zHkblZT;Y3?^no zUtdaAR!=8#1BaV#KgWBIUJ$K{ficAfdRD#&0sd&Sr0FWJ`OnG?Xz|sLb%Pf5L^a1n z7C9w@YyYY^H!I7_wfQ)FAdhR;ujL^>U!0758i_IV`n4$Fknj-{%*t|w5p>F@!;2h_ z{oHT%U;B;QN2<_fcOWGA8ygtli!*;dvdQK(^_t^!S3JMJjqld9O8uXI7FmRehkowZ zk_96&;eA#1(61Y2$4Cf)Aejt74;=g%QMkRo!hrD5pfKFDQnEU^v5^=o6&@)hRgH`Y z`zu}i8BkY^zEjB!O`=l9iaD-?uKQvhvXFd%~6ShC`SUq7^+rml6v@E(Tu~8Qt?;PT=? z!OO_`wYyrQYB81AYxBqinm~%^U#V@I1#!V5f2(P!T86hIHN?P&x?0w~PYBm9;(F;g zw@=aR5{~fD2$D(h!RD_#*2}p#)~XIu;aCfo8N-#bRC??K6XKV`i}6uUqXnVPXMx(e z4$D*hg))TPxH#fF)<-7WvIdw$J7&so{Pb8DXfAT9wxY+X$8}VKwIwXZ@bu2gkS0vl zwaUxFTo`esTGZ_Vs)lAkY8@HLn4*MM3)*+{4aDP~3#SG?P37zmxnv{|D~hf zTt~iA(!YgfeyzMEdh`v7sa0| z=Y2*%U96!w)_E);wjwE1nMY9Fx^>k$w&7x{*B}o{v1{}74}a>^xI(nX>9g0JSUve` z@-s3VWSw7C*BujDkm7akvs;#A#wvRItwms}e_WV&zc&>|7JHUp15k==zkmS+*J$&L za+?l=w$d~GEeA6*8n+~T_(0{Z%k?)tA<)^Sx-d?lK?2R`>Z!g|>c#jr?3ri~OzrA= zrjJB7%Ha0T7($`ea^pA%@??j+DU_#{?kMS&uChUFk!$7(8DpE5|3pJEWOt^b_r87j zJKMDQ4x4yo2h)7#8~*3Z2&N5WJgeD)&A;+VXp78+m-xxf38wnh&%FBjHiTHQ88@YX zgP#gRSnS13@@lAl{WtNwHe%KruO^)NRRd8dN_z+wey~!q(Q!lxdaBR#x4QJb`TSAn zl@M=t|A`sG_>Aw=WJNrN&M5eum!ujzeKT%BYp8hiA33)-* z{~WDSr0E#h6WaVtIZlV2%-kNGah%W^H%iNIY;>4%ePoQuc3Gd(GJme4^>4tzT>#Ke zlSNx%+gGcaM57sYhH-lyedCH$V8!1r@c2{HUw!;2pX6QOGU&0DxJyJ=SJL_>QH2&d zs;>x6y37QhSG@nhU1nCPfg=n%zj+URdXBe>?v2q^@<*1WsQN3xQP2D`vLj!qN6gQs zTzHi7@GrZzB-q&)m^6E=ADJ>YlB)84$p7FGz1u&IA5YoF6yie*=a-~lPPld6ZU~7#>gbm9fy<%@QwV zMCeP9o{+URh%Etwf%C*ScAbF!y_zcS10QTv@4|=+E>VHj6FNGk3Ilw?W+Ghj34=ek z@IM0Brj6TfWwzBn!O}v{%=^i%EqC;Ftq3j>_2@xH;^d?Qr%r&eb_AEx!q_6$-Wx9q zwBpY6-szJoos~(?zYJrri#bflG5^O7C=?gtT$Qp^*~0AYo($eP5+gwul5w1==`mM) zm4!yk7av8(j-z((x0C(K=&`}UIM>>HidS@XRG8S_(|#OFyK*J!Bm#q||9E%>2?;HY z5OIv*IN7?jC~Oxzf01q`p1>{WDp~I#5nhy&Qz)lVusgG*MN53Lg-ZVV*qNU<=pWe| ziiVYjhHvs#nuHAw%dI37CvO-|;YvRX7eu-yCR^O#M)Fa?VxLT z_~8yy{mhW)%)nF&wTzLdsygj#k6E&&`8+?%68j~)Bqbzdkdw$aF_|fByq0N}YO}%P z!mNJB6fHgdNn=x}5ADSTm}ywP$-A9UqPDd3b}Nz3>0_4COMIDY9Ro3?)mo}rLQ?fz zkWo)qjZkeyffmQ9_a9#`TQAy9++o^Z_!qJlBEN7NrAX5@5>ik0ohG+QD|3k7heQf# zzZKO$SGqD(^7+Yta+a#3b*B@=7zP8Gtyb=?ChPXY?_y0bMD^gAV^SrgCJ}?fl+`vi z`3(f(3;c~h(Or5>-xoW0rLOwBP*)+L5;Bh4y}#dDV_5byN>y5Va4QlJ1nmH0nJw7X zTb<5r#lmnBO8GGo^}@z6J)`Wx1%%H5tZU^PlS1|X{wjc|Pt~V~6O%ZId`yS3u9#bh z+;+*#C|G`@!dF?>(iHJActM0$|H@JIgq~ITw6h{yNAwacniK3S^mf!Adfb&;^3V94 zZ4XR*YfuvznJ0MJgV)L>kv*wD_2>E>9X&Yva$S9P6U!F)HihIW2|5-*UiP~Mr$}3{ z?XS4xBn#g3;3gcxIOY4RqB8Z#eiwNSA|u)EQfe6YRJQ_VLHhAfzYP7vET%u(tz{&{ z<(?pJsnW*7BdZrD8+|fUrFx(|HQT802yeH~-J7OK17rBlyxnrV$^i#!Ul(Y}j6QAs zZhLsFE&A2PC%&s{w632}fB(-$$HiH^lN|suRk;}6(G`^>L8oQYZXmgp=y~1tpyUZT zW~|2c+?4lKQARiwW@ai6yNc3WSM|j5R8`gtF6xK1*h!u9)0L1y(~58D=i%NH%6n^l(Ja3j*pJJ z-(x;d`0yV)hoYeiOl*991NOPaLze)dZpUxYkhF&V#X_r7U7fwRI#p7}LuHw< zEiJR%-O(SF2+JLSg{q{Ak)izCRe-C6)rCsJI6zsuCfTce<0y72|E_cAFxka*ADBq* zp=*gxK|eMK^wY~OV0*p3{!ITGopi%Mj4l9X=-#k}!m}c#inC9(Q!37U%sPAp(rd0x zkf&p|MWXx4>!tj<3W6XKLY4=90}s#j>-`cg7Y=tFhUpy1vfbYeb#+fe?$6Q#4IQGB zwwX>(R@c|~kwd=US^FJ*vSv78CU(#AHoVrvJ9s$^(f_E$JDY)7U?zTjIB_29 z-fdP?zvY}$^~_9}KRx4#iUU#p{r7j{{plJQiEcCD%d<0byi%6;pT=`G-`8!Z`Y2w1 z=qP!`NYVN27Sc+k<%2-dpiej1haTnM%>D?Sy!KR1kip;g_gNPVMG3Q=$HHNwdDgh^ExFgbmT4F&0lARaISgLdsU{t$~&#;o=fC`|dU5 zc8#h``H9{ID`f7|m*T{Nk}=>66y9SX;EJ}Ehn&~dMVAb6EFS-lW2*NBYWnOf{$^e2 zP#tiR#z=e!*I+i&>x_b$W`DY~xhdKPvE}~#PmgK&`jVm-%Fnj$s9z!$wVya$7o)rN z`HO$!q}n)GD3=TyNe}^_#2^#go${tsIu_d0hNw8XP)1bfZ?sy@%r5>MDt&BSdb*Zr zX03WP*nMhC#+7Wlh0R%jj9M|%&S6R3Xq9s#dFE8fdI^c%lb)w;`Z0SSc~AM5D9@7m0N%j!4|yS2rR<&)SHaX)!Dx5RfrsS@_J2f_$dCX?S( z)@58>+2p6x%9OG`ig`%_WDcz@Ef;RQroZ)2I|tFw2t%$vqIH68+7M;Qycy5+jtHaS z$2)dLtBE`@^)-;W_0N(Ioqf0J%*^o4`U@`~1Ywp*(KrY630^6OnCc^XUiM)T)Alf- zgMV^_noajDrvT5PqVS!L7IN9}_zb}YY3P+T7BQ4|>Dkrq0;AG?cpD0y@|Q4jBb2st zWNKl;B0zqeIJh#InNDK5Qmp#$e98f_JEjevK_bO}i|JgN!o(kAMg+uE*J=sFv+{?3 zO>}6dzBr8B=em(0xPXf8vHQcwUl>z&>`e*cVeyne75pC6wk&}t_WaE2jz{C49s>lB z%E*|ufkE|W`q&~%dI&k3+}!&rQ6sIdP65VdbfvLkn5G!r6m6^2YAD0V_V89+_Xm6w)V zuoiWF=&Y)poYu@(-vQq>j(kI{Yb)Ef62nBimU}SoN&fIY0gfLr-pZQZGn76*mujDr zUkrmNAZNq2Z6YUcIcV$lSMaLz;Iz}{!*&EoyQS++%R$u4QUi{Yhrj6_6xx%|Rtoof z01EEJv#!sFxK4lZ^_e>;V>zOY92a<1+v^YcP!|OWYg}QRGCDw}5$HLs_e!E(ny&PK z*z~pwKvTZZ{Rs;Ri9v`*@9zO!c^_b3GD@ZMyNY@F_J(CY2Ddt13TAS zDEx&Z*t2@$jO?!@oar4JIe%EvIug0Xx18r^IsV~Y;2<8}Z8vvqB0Vj|hkVC$pZ_1Y z?#;$^5l%*}uHqG_M<8xRrs+zvjmTB~PmV|)myBhQZjg7+m5}VimF&(0Qe$YCvNE{f z%dF@g8QI0n{@{n-31rpJ1euxHx}59_{mi@ZhxhI4CFq-BX4>1%?46E7S)Td*V5Y&r z_#Bf#$$GS;wQJ{b&f>q`?0yue0GS!kKi1+FF8rAgv#`4MnRk3EanFJL<0q~6Q4vbu z-Af}!`s%?? zBaXmZnKQmYtkEAIqaC*Lf7&a^%QnVPdL@e#^}bBT?h`Ll0{`KiNA&nP3snOSuIm{b z+sD?|W+Vd&h)|L?eg$$sOkBK2QhNhE2ok*Rqmhz1)cm?T27CRpe)*Cp6!M^^#}uym zuaHGVSZEE~?&=F{C8ku>Wp#C;1(R&gcAWp4O_iQ;P3oF!{jT(9&qz%&bfs6C$*!mn z$m+%RnQ?h8RkazM>$gjuA&?EVZ9D3vnX%@6EK^yzuU{|t98p%~S-lTs=55vvMZMpy z*0iqnk;rIrA?d}7@5#oBx1{Ov9k$o=%b0dv*7`bhzw^9uS8JS=Ad}tgyUE9e+NDf& z3;YxKX8L2REViKhZ%lEAF+r6^#M(rh{d9ikEAvutdZU#0)egNWVP@^d8U38^fvUvB4DAX=TX6CNtGdEvAe6*R5Y$M9AUAFsv z6%gyqpV+V)lDBJO;~?(RFlVhtcOC9FQgm$NPOp+*_3zI!e=AiV%p)4iaY2!Vnx0hz zJPt0Ka*x4lH*{&BVvR}GGjpFX@l0R*{!Z&e6xEfk{??{I3`+#zs)oojfQNr-sDZkW zqpnj9oKd?o8^r4o<^oK~H~n=O_<@O__I~(lbD76bvVx-whiS7gsyLEx5!52vNKjqn##D zGW5^mE0HI7OFWBLrciwLVQMyB36>>w`4))H?yrGF?|5G9C*J5}(S2;(WcULXg>9q5 zLG9Hdr~{!txzXL0+w@Sy(M{2em3vV24#mZ6-zVhbJ_rGdJ{%isM(8h0siEl^|J)7} zUt}M>Vt{m+1MOU0?Kkr7YH9mV(C}Mf~2@Ci1>WHiBtfPhb^{@!rCjl#Z zIYkjTCiYjfo{^6mMI!N3{@I)o_EKR}2T?4%G_#ofCv?pV9bz%|_5mi0D9bWXQ)@1? zWztsS{s+ubr&2-B;2dW*F0Zto{27R^0FMlys-bvBMuiE}rOW2kN7mQ5{$^!HU@!Bc zJ$O&~b(iOw;|00=Dj-QFjQ-=K;5E@yebfA#RuCUGmFI#|+=rH`&x)`WUiMThICYG- zyFI28Cpl5M(!UMyecne$TRbr|Ji!-zF~FGba7!G7;9zFfQ&9NWEvL6dwE7$S`1~-k z1!O0cN!16+@pkJYA2e|eUVOiIIbkbm&-tG`yq5TuG4(cmYOb$tUsd8>4b+#ed(3Q6 zbLD3>{-W(*xT~$L{evDmQb)k0`S*VecH?yB42!7nNoen}B|t3;4>o|xDEi@=16s;Kw7Rmj>k~Ap87&kjMZdInPg1URJFwv`AQ$ipZD}^@sDdp&dDHes zS1uZs>6EQw?PiU=c!aU2FB7>Z+9#P<5PiI#P@8O*;Z%EoqSgNNFRa|B0eFvI|J zUB+|hL7bdXUs3wPnqr3Abe?r_Z()G6uU)!aZcinFW|3_qi0S=GgZHxhWucZ!Mkr+o z>rS8=%dP0YsKq8#>qAfUrw2x$VNFYqjOhpg5!!OYxrtbJ*^U#>4n^9NU$vr;B9UBp}Ac|A-PdtT-S?;D9F{?GpX zKj!cTHfUCbX>vHql5ukxnsQcjkNDMOhNOJTBzWmi;q9LfWt)-w0umOKy|!R`&8PIp z(JUJOoan_B@-F@z_UMBaQ@!*dNl{KB2j|SxguqjAFUcc%!(5;tpY|IwHKYphx_?o8 zqggsJwi3y7%GxYaHeF(e6`c zX+_q-a=s){y3&d>NRtAE8YXTf9yE6flf8B6q0(NbFri~lM573Tt z+b*M#%GEE37v&weVo47oos4qQH1{cXc>+DZRy|XwL?-pK4 zhJKkxsl*{V)E<59BkIXXNfx`qnpiXxML1^892-d+v$m@b>)2vF5uWUHn=(sRs)Klw zVG9LkMIwPhUlX&z^9FV3>N6@Jgs8tYk;>p(;*d|iO-G-y=1B`dV6~};LE6ToRc7x= zFvwR&C9Ngc7QprY4XiMG+|`VoEtT`Ds7PRtMyV(v4u(r`$q@*RvJgG>x|mKV&$gk? zPa{2e!Z;(+kL5-hDw|A;ZdslP%-;qdc}jk@aLqoK2BwhuJJradMtP+a#W8W=A`bey!Jnpt^cz# z3y%}`hiq_6W3O_sjwg)RQI@CDTq78y`Hl?Gm5z-)?Q6w5*4}OP?=N%3F}L4G3UAHr zjxE@C5i?{F08;PtQBL$M14z+rs&CrKUdI6&7IB*_j0L^r5zv)+OHH{f96^vu|5H^Q;~X zuo8(XFO@z6nN!>^U7akJeb%vl*ReflYFVLm@6Z zr`6S$Wu*Z$AfDbC+l?wKw(i*Oxf@CEob2E_6P3Z`8MZxYCwW&0L#j}6S>=dtv7vpmL`(IxM<7k+xlL4jZ*ZGN;c|R{Rhsz@Q-I;5} zsULg-68O|(5BtnI<6ETE%qSUhN_76!zkI|A_)}?#c`~&1_abJdBG9kI3?NmDw_Q40 zbAmhnc;L!b`aKb?45iC%69MVJkd1(HBHW#~E4)Pu8-|#wca7?eb@L?Cp zg|6>2MyTXelAqby;L7xE-7586C5$$JsUOC_+|3=s77jxu-Na6pUPER z7*``zO|`6{EX9BFo-mCzIUB*7d%1FtqxTB-sceOB*Ph^rbR*$D->s%(yL`K})_n>3 zt?>e*<7uQAU}WcHl(S@R=ZP~CWn@y!*8i2E-kP|_X*~Tb>tbJ_GIVbHh*}c1VFP-V z*Td9qLYqU<`PD$^$v*A|AS}mTXBEYFKR$p5lYV~m81=ZYa52{{pDo@^Yy>w@ZQWj8 zKm@|#Zqb!~y~gw+aBj}g-hSM9TF2zZZRpJy(J%Lx;xltS3(Zgmexcjq*r!7i$y7A_ zg}RE~p#m%X0UJIks;E?VoFRB++Z(AA{5@v8eJ(J*6Fw{Dc=jq@lbeA>SI^pnxkExO zJ4_tmc|x5T!dJJ(#kF>|xB!h=y_VnV-wBp1Z~(;^<=Z(`2c-|o{dhJYF29N{m(Dew zxTb7ng_D~|d1_cd71@&?_6&M5tenIbVm5Ar<8%*fF_Dsv7o~aiFCS`&w_&B^Ru5t^ znhJ@vENW_)sU@V-Fy1ftc)z*PMm38b1bXbXbFZYZaJp2zt1BMO79KCAy!Jf^vwqy) z_xF>gDMV6N{8B^xjLQ~UJCy#O>EoB9Rh0Kd&10E-QHnC>U$WhiUA1J&+j-zxivzHG zn37qXaZ;-$Cni=VOSTNcE88lXa{SO}TTG@Mqx`6w;L*Nf6mN{`W!g$SHAJQ8<#s_N zcOThNj@@D|F9lXF{$*%i%dLhzgd9_0pQTK^8Ex{b_B2P>f+`w)8l(|ELpN!fl~N;1 z>X8hDnIEt+7D2mGHSYgQs0i$zY?^xl$vAyi#pHLj zG3dK9QG`Dewc~qgTJ-Mpv@^cR(HkDkje*t#hQY`)4RgMvX?8oHBeo`Bv17txcYgMS z-}TGk>EhsuB-=M#(-S{`JKGN)+s^}n4FSpK#l7D6I|@-G{ZvA~H7o&FpgC9weV9-Z z8=0++VkkNJYwFi)*X=%8%L>aKQmct|nq;PZ{A%c)e5|Tjr#}WV6#u}nt&qapgvG8E zY=WYR`eiDo3MFZr02W-jJG~=Tw+*O}@ zGm}@iL{(T%9WL%I@?@N+%(;awGTZE1OaU`LMY>ll7*jr!Pw-7afCja+T`LB$x{(7} zG$v+=r@FeS=beLP_r{%HTn^k3ugzpIhO}g z%B79AnxegrpXyh1G@0MRq5T)3`s0_asQFGO`t(7UNJR;BH34&DFxgrOfKrW3>$Vp; z-A7~f2C=RJlemFsfk_}J0sFtT%Y!Yl5zr=0^L4bnFsyxXj%3R#_3P1JyVTY+Uwdma zbSb6nDJS5wE85TDmb-#HBzV*EUytRU;|t^|Mr>QbQEm(L*N#~N60L?oTbK7)q(l*u-G~w?|xsJDnZDoK$z$nf8OT(wq+VOSY4FAcw z#alT4!7=^u^*hx>cECj95Kvw^Iq8nK6C`(Ui7_OGTXyI2o9D*9X`Au+qFO~1A}F|B zLWs6!KVy61;5o}N;}Vu<+Yz;AH8*z_Gvn#E#5KEFDqK}1MD8*#eG@xEdkg-187yQ% zH52LH;Jw1~PbwxEQggo?un80WZ+yAl0!i)Z7#BymtBfKx5)Uu8etW-qAS;*oDA4fH zx?1pb*3&_g>xCJ~xHM7GO}Phj7|6O99rtPH;Fmf{PqIvH3Z!m{tYFF#JOi-rJ>K4( zrN(E)p^A1z4p#&S#be#&*np3cm!`f61Hc-kg^L)?BBCD?X&i9n4jhRTfJ>AnGw}e> z0FP`eWxUx}M0sLS3EF-Hwpxz@uHOK4pt6lV57--l#V<|xuI8}^o34uDGPF-e^jHR{S?Ai2H!f!mY|Oi7*vwY1I#*cjM?lz~2&Dqn?A6 zz@LFmhD0aUy>Kv8$2)VSz+r9`IE}hI0p6-dWA4CwYy&vZjTLGYxgAef+X1n>euGa{ z9~X*C0jt`s>+ThrgDPJFGMb%rcAumH80qtgz6F!xvz0AEO~=k6(O=!5ExOwQ#tcw% zt27T*45+P~5;O}=+t`Z9S4^(kV>ZG-Mq2;33x0J1g1(iV?f3Wxpu^EDC2?R{sxg-jo-XW=5e0VQT5+_3a66>}O?39rg%RX9~>jq;)4j#)b%3e8VS z;X<+0&c7y5vG#0Wp%`5bYPaC$K0B!LQ)9?LnwPCJ{pQ^_nO<+zElYEE6DTwn1Zsf8 zQCImiW3Gt_1yHyl*bM78=P zFN*&gnS^SG`0aYNx-%<4_?qPt^C~;sFi{qsW%oO-7}RO9#b=%2F<=GwbDEE>tsQ6! z|GbkTq<4Q?Uh2bkgO1N~a^ud9MqE786_O2=Z=5vk^zl13jHpg#c&1BT>;TWo-=o9B z6OxH3c7Ft$sF50XU4fVJN*!;*BlxRSrbmDy&}PfI7?rw{0HVs@K4)0tOC9BSwy9~e zBu-BI?`Oy^iGa)VjV-JF-w$~`w%w&2|7A_lRF-TLQ&SCMs6-xsB<;Q>CWbVPD`jhr zu#NQyuH2iGo7^#zBm%nUH+#2o872p zPI-)ZqjG3dw`R`qmIU97Z>if#+Te_*@=C_eRwId=G;f8VAT6yfwWRnVlXg)dx9`sJ z@&*P{qbtulJGaf)a6a{}YpV_HfC*CL@vWxy6_DFO%jk_HQh8VIR*UOy!J<%=z%x5)??pe z-i{1}dGAP&U0$w;?wj1?F@=O^2-NgYJH70!b@^5Q2dlkTM1Ct)iZ`03U>f+Y!{fpU zOg!|U7aKAbzevdxL@#^ABGO!*DP2IFr7#Xj!U#Ba5)D3HRAj6nmXeAVuLms8BLJHA z_l|&zEwaV6A6o%icAQ>^>T*tXinMBy-Yj#;S7Dd5&r$`%D?MkEXsACV~&i70%MpGr@pPN!4xO*)#@pqCJ7T)m6+?kn=asT z7bfUvxNs2*65N{do|HTeO~Y^HMbjsK|_lZtKZ2i^a%v4kwC01OR^2-P4#wbWJ_NOH^G|XbHX9G;i2L~(Z z>C{h$v#JYsy|K<%Xolz%tgzb|&+D|GnbN!eH+1_FtD zW)f&;QQTtK8!)-i*TlNpPk6GW*=ghnpX@wsk90p`ie2ru$zS^eer{ikE%N?FDsg;} zk^iIdvNi0;U9k`4b)Z^akS(?y7Pu*xoh5Sv5>2X!{>&BLM%^M+k@jclSo44~=RRT{ zyY`;i@r9B189%++a^vc|qm83IdHRucy^6!%^UWW+FC6$%^|bQ5#XQ$9Zk62H<|!#0 z{PPxF0!-&zRZov-rCCTin9sANZw6KSX`Y95-B&f$1f$1WCIiboYU?HS)6vFraM!5Z zzO~~i`r&uDQ-)iucNVK1NAg*&7Seqyi+q{1-Y)+*O5}}_bsM`nnNnCG6*+kdEaDDF zF5fg9H|*E|GrV6Ha>taDgV`z6REMXb`1(8h$3GmV9@C1S+Bl4tz4V+RyQ%iteU$}; zHWv52S$0qJwz6!wpw}}gO<|S*PR@3bLlGa|#sWTP1T)XZ@fpEfh5QYt%^6|9*QSmX zvdG-s%e&J3we-L2DVp{pI;v|nR$SuG7#$qssMH<|Dg(v7j% zDcBV?a<2sh?2~*8I2r+y-MQe8<4C(M`X@h9ft%bb&fhRjLAD8GqV7OBcI-WY((;|R zu}Nm3u1}yaa#Jr&+A5GK0WM3x)I?idUH#Vv7K{?;+}(f+ibUq5@L#lT?B+5VSOCIwt73<}+IyE^knS8wTQ%8bb zbd5>D?z0VF2fLj5ggi4f<5Jcev@{699Axo{KLji%M*wQ6=ruV_PyM#2-1^4I^+IGL zO=)JWF0JQm!D`cGWYI>`saXs-I83Ul9H1#rZ5$IjVt9sw39C0ExU#oB7J?8R(VUN$ zNNKOPoX9T10-UR2r+56+fYU`$D}eAT6VtcD_5pjk++}fium35>7WD+jN(jZroATHK zhby18+C{^yMPNie@~vjs_GG)&FOi*B??b-l?EBY8>&I=KT*AUd&YQYbQirhYn?tpd z(Q&P7krj3!muyjB#ho5|u-h78?C<@nbFI(I9}Dt&n$R-rM^T9ea$crN>fm`FebceN z-0`OR#T~v}Z_B-<>s9$*4O>FAj`nx0Zqd?m-WPpIdoq*1$|gnmn+o#&f+4pgFHa6^ z=~3XC6ZvE1(h zOLJa1FJHhW8v&+5#+BR68$au(bCzVtxU}M1(YrR3P~+dQFW%TU?~jAf0BrH-=m_!4 zGCXmrp49Ib+wrQBdLf=OEWl4f-j6-&BD=~iFV^q5=#|@&7wIWCo?p{<=} z7SiWAGy3qbh510*&I}@Mup|2V(pcP00ep6ih${)u9xaXw#gA7NFMqHHdk#dU3M?#x z)edLP*NAHeJcZ_<+uKfJJUoNDf71P$V(REW3#<9;clBoAXBL5PHEn(A)q)H4HGgxU z0_YLIcf2v6`FP4z*V<-W>qe@7~U^vk)Cwt`Ha|Lj0)ht|1 z=QgE$Cj=fBmsoSa^Zgq+I)0(Gal3;7saHmrd=tVSCqCGEe!)89G zIEdNnmTj!ApDyM(y?I)9Vyt}5Y<^&+jQue|u}_>SgaOQUZ;`rz{#zsLX&YP7b0L8@ zwP`Q*gI!a&Ib0edwTf~lDvVZKt{n%N*ML0Mfu6&)kw8Ud`($9)V(y{T?=(A;+?o2T z2`K>s_o_#(UpA=Cxmi*23kp_`GuOU^j@YC`UX=w%T=+}CT^s*n^Z9 z<<2fopRRWT9ZmtjSm%27NGX&}yEQATm7a!S)rSt`cyAI~l!M$H+)BU$+_jZ~`_%{L z8DLcV8Td2)k`jM#vKN%j!Iw1a+eh^pEt8M#oy!}L4=AvuLT0>jNL8GFnEN#x{vkAg zowZZ69*F?#$8g~5jA|WLF{bjiU_|Xjusa^8X*dHE7h+I()#`c`mfe(zY zn&6BVtm(rCGp?8_L~e;B%?8ZvTLCh>#~J9Cb`jg0?K5ZKd6B`U%AbltnXeyDsOM~Y z0wy(%F(8rvrj0~^gU#9-N7|2|AT_FgYjhiJ?ww=Xx}J4fo-Q}}$)a+7gZMh|(LV5$ zLA~8~1G$jHOW^eutK^;K8{t;G4;4#pG7WZHFOVt4k{%BcL+>C_7Y;s&54&Q||a;;0cF9W(f9b-X#8Bw+IaXpahZ z*ofxN6D{p}rJBMB6F=sTLdM2d=loi76+O&cmXy}ABQHg;1T+Eu<6^FK3;s)Ksy8F! z)V-w1xb8reOTA(L7e*;kOS+eXH=F{NBLgrO=kRBF629jI2tXq&1}~c?7X0^ROTdTV z&mb##ykmpbXa1*k3xF*W|7jmOH9Cq_Pk@%(jJrrmfn6Vyp6VKdx#$RQzxJY6Ge~ip zumnPwQ5w${+%*I9Y#f9oZ$3wfue7QXPbHaJMAit9iTR8`YP>5XX!fVhj~YI<0pn2p zV8at4xG^9|KJ0}79vYZ8*M@@_2TdFVSjw9Dlgy>EXmR5p*4?GSA-Dpl%>dY> z`JBSTJT?|S5{$hiCu2$!8aTZ=@Cb2BFX}H^1O$CRLU6r{4U!258e7);{4LkInwlhs zN@x~u0fzV!?SkT&=Nyl_8~e_vf$#Nc9Fum^!TE-E(nC9KpRpuhotxZ^+k8X{J23xU z2#n;i8P`r1HBEjYyM(?B>>NnR$0+PHPASXCDJrfrY1hXfjwYw!L#E0 zXSjXXFnX!YDrsC*MC}MO_EDT{lxXIPqFynQF3DxSUag2@qAbS)NY3M+qefIOQ6dcg zsk9?#=ALZ78bkXjObNxpLCuBua%HFA{O!SZ3hai@$d5@w5Nrs4PtPCf(#ere{DWzp zoSthM2_ij@VsxLMw@~DE(kCVIB>{Ua7z-Xg2Eb$n5sKrj_*s7g z{n`g-8^+#ww8vRt#6ORbneE1LAJX8Zg@S7or--dyZBv(8D8ew0{umQW`VTStQ;gI`)Yai{E z{OXib5-4YV=5JA#Q(4`{R`T}#BMN$5hmXugyr*IVQy&rxFPX;zRT{$EbU_xy0G%pp zu6A%3)%A>e`K*{ul6z}zXATf(fQ~InuYI7fNRz7cd^u&bWc7^&)+5-4c7rXS^_Y$#0-fJ5|l>aeg`)_1(27yTc=u8a4 zSFpgOBqS+sj7{kYqOGa`b|BPsWG{yvg#$x(>icF-e%>B*sL=~Q8_FQ?@OvLFyNPid z?E4`Q#-;LQWcGz2Ni7cF%LkNxFaO@N;%IL_E&%Ug(A0RaMd#{V@Cb1vB=3T8OCDqqo;|nVQPPl;+i?b;kBx(KAh%7o3K*!hwxgIDW zf(k5vDRbllAw&oRMA)a&fwBV6BJW4$U*Qp&%}J5TgyOefzcO_edJosMTff`HyS3n= z0@x?ZC(^1K_M_b2#24@OG+cRrjRP);0;>nySJJPn3=rktAX8uqtLx>aeIO02!rX4b zM~WOaw1QDO#Gw%go1RSjc=-%3Oer|^uO>nDJGlrIa$dKlmo75@9<1mqY`M=JX&HP6sG#=kK6^ z2cS0Kqoo~H0=8xz+MFaJS|oyk%_X;`Pc0QdJm(O1v#jQ&B6|ln)`uo_! zt`#l2f3^*JeBxUipg{iw7~PYPb`l@jd|2ALs`PIlD^qNEgn;7%g3L21lpsjzH48z>eWndjz}QmvVifPTZ5s~t?Q|vSlDu}u{9gOz^e8Gz zgZwHWM#sp>$~pnCv~{qdE?Ax-j9YVal+$-2h9CfBLn!^XH~6{}^%A;hJuw=HPdcJ2 z?kPGr^mBDRmpXfY*g-8*imniQ7Y|W|e?Rm1=8S&LSX1)6&v2O-K@s21-y7d>xnD(2HZmt*x#d@w8iTz%i+^yOJOfXk8ykJl_=k zEP`8A<-seO0GOmk0Sz;G;urSx6u-O5*E?RKLwA~-rT_s7Mcuwv3>MgJZ2bjE?mp9# ztqO;JeDKdnD)5;eN9*Ly`GIs5~r{Fi_iv{ zf&mqdRP4lXEllbo9^PAHrG0R0eDMkrYyudY5TYk}aSO_-mMG*@{ftYBM$#VNT~)fI z^DW-W#?F@pMk6L|>%M9jk-0X5Ua(=rqL!;Gk7sg3yy}PLo(ldVKTaMM9!QO4q=WAr zL^QytP@Q-Tt~it!q|dZ<5HdDtJC%7G)uftf5L?wk+r9M9GF*=$!^uR9v}M{4_MTF%@+(yx|WDt2Rc34F{>c zyHpl8>l-uls5TI99AI}k)S7w|P*(@i02RCTKj)0hfbk}i^U<2zjgpGGkmrEvg$ej+ znK~cz%=povt5T@H*JP!6ALjYC6?RV{*GH<4>SRD3Idv{*<$mP@%!aI1=6vuGN2kq_ zZFe4@|A~6|8Ws$=BbC-_zfi!JPep1`$%p-eyfC`;#kb(uSf7`{44wXq?wKr9usfQ7 zQf659m3`b@0R#Czt(f$2WP2_EC{*3%JPi7a_MQQya~*U_Xy+KXc#nq1^$^g&Vrb&3 zQA+*58(yK=r2A+>unvmKP2S?LW``R5WWINWvXVrBR&E1_4GHQ3=jJ7&UNnWR%s&JMS>kM4>xT z5%@gzbM5ycyMXZC8ju4rZl-6wZv51aDfCs{RUUBy4t+iOPbWb8hyIm*(rvOo2bsYq zCi%^iCu+Bf{>*Q`3ie>)n5B(usm9t-4jlHQ}bX^fwy%-^$t0;-G^-c7K9`|K1dCexO7lZpAl3MOb(#6^=K*$6xfaGeqAgqI#&x$1#IGp*g(T4g++OQ zs*+@)>LM>ESM6?m7PIS$t_L)rA8Od-QWsggQ;JKfi_=Z;q48`NBrq}Op8|ra!9e=U z=iOSn2A6y!n8ycXZ`P@%v3vtkRh1w$-4KP0jar$%XaEq^;L+Gr&z}kFMZ;IqkEiOq zFYC?2(wME>)ff@9cV=}+Ex(ot zkc|>`=5w4>U-8U_kCY_sJ#mV5Zvav?#*lsJPU7H5uHtc7*9PtrYT?OI8(5^6nb!Bx z_bGvf=H@`xtTYH9$@pZn7dMB!V%6@HFrYVwO}B*5m8?0biYfvrrmw?`*k`fT)vH@m z@pEU1Jk=_XAT`#6OkJR+Q~Cln4hKZoD$2og3(tcVP5d8|Mfw0OOd6md?~_X}l`b{pgnxkge29T$m2#8q>`#FX<`t_AJg> zpqAYPpAKJZJLs~z;Nxqks+#qQL_}=vSeSZcaf3t4=AT?e+5>3KL=T>WM5Z7+yP||S zMMO)0qY|+M*cL_bTHS$zUT}fiX4-_f6`&*aK2J=5+x4RfD7rpe)Ve5hF9Kqp!?QjE zq1tT5kTg(vi>sdUfGnY;8m z@sGU(QHBQO6v|s$+Ah?UiHU7=cDb$nS;s%3fnCbzKav#WpyBv4D(U{nfuaE|c49YV zAAS<*F(%X3T--iaQTgS4>GJLK!_I5xQF_z~JxM=3oesee00CQ4$#yRVeXy=Y;|`$BLK$Wwch7iR?OQUKgyjExksFAL+03%_cr9T#wr z5E87jfw?vc1OI_YS?)iwAZ!$tct{uns^Pukx0rOL1(Aaq^uTbZvQzOdNksqYQ?o^_ zyxx^E7nAl6&w!pH66pS8utXpm|EQI)iF6;O^Ui>e%RTY_Ct?7!%hdTO84^N{=Qag7 znGe?Rt=AUIc`YAX{Xkj>8|cF}?@HVfImE_5p1;(w_RNcCQ>MTA3JNBU=ShI^+N}?OY-wng_iBl+l^4Pv9o>LE`hx%guT|03 z((}0bsQJU-nHsCgzIEGrrA^w6r{oc+k{q8E9}6*#se#Pk=xA`cXHA0lZIxqMG`%Y& zpwN5uW$gUiU~$^{NCL-cN4@xHSyxUk+~Z#dkYS zau0V+Gvh-dUkzU7HNru9J6bq*QlIv0I6uZeKu_<+1~vtcKc=t{Mu++peygfi?_zbQ zAj^ATB}iOO`|c0mxDV;%OqH1iVIu+WP*p;UlYQ5bQeqFdIeC^=`ko8`e+U`5X+R$S zg7oLZ<_ED46q@`+S1NyLvd*ZGaN)PO61y>8UL7rFHL~?L9C&+s%qa%bI0IG(O!6Q( zQ|DHul=BdTB9y3zhbJwl;Q>lK(2s`T{QD|_UXoWffSB~w7_$zQodp=3?M?f?^eGd?wc`yOz!I3EUmtQQa?FH^i* zBJTqYzu4HWOMD~#fCb3iKMbCT$FuoT|1G=~fmWkN8Jm#R9|nkkUqsoC2Q5KEV*wnU zsCSxqVR-#ROZ!|5aI?c|H0W=^kB^NxmwoytZELDzK`Ng1kqv@Pvz4Hedvon%myLlY z1+|A-KtkCuYM=7@rXx^e=ug zt)+Z7$DCT;ZPJymKSD%PTi?tzN&w#{e@4hyk%X^3daA21r(%*Z=Qm>qxVa7}JQ6_{ z1}wBA_aBY~bRS1c60G`;9dY-bf3_fbnxpP?yaIS3LWm#8+QTu&#aC`l6_yp)mLfEhIPS-tAlbp|2>rlc>6Mt4U2* zh?u%QaCZsMSlxJ?3*-#I=azr}KDc^wDRP{e>>6X;yW}@FcOcn!>h*vCDk%6Maeuvh zd^GfBwnYU`>v_t#@yEcQcz%AN1c4+Zr&4Dvp9K+3wA2SS*vv267E3UoVjizZ{KWuK z{Evo!8;qpfGmERemKGa+cCZGKSKwSfTlONyVtA)Jf9Z|WQ;dhiyR*kO<2UXl{stY6 zc}KQ4ts-Mw1_xJ=6hZU^hvD75?Dj^#_f6nZ@bj49=g&m$+fRO+UBn@wFhm;@E<%UD z$BhF_SmYu-1qWA3U1J^9K#mMtQvCQnDVmJSI%(k%8QG~YCY0IWeJ2O(VOABH{vV65 zq7TGz(bPt5#Tt+#JzW=A1=F}d>#`u+w?;uG2tlUf<%#1nJp5`+>$k1%1=3C#<0fgr zEI3??$d>@h+B7%T$O^6)85OpUtP_oUXuYZO0+Ot(Lt!tUqb^VHWG`DGCITJj_SJ>LzwO_SyGH9xA;R=3{!C~;vG#mbghm`FPQ>h7_PJVd5^yNd_mcZ}J z!0ClS4-*sm?jCskHc4Py_1#XVF1E!)U;hOTJGbm86)raCx$B>nLpu5K+D(BC%*jx! zxYjT^I&WFuhI7Z@aJ}eGxyD15xSo`&xuho|U@Ee{ss_r?|!cNHynmu45TI6S<*4Eg0G=0v`8=-+38Il7*KF^QWK%rqj#2{XprnMCT1@1 zJE&oJH@*^Ztriz>+37|f(o|U)&TWL(9V6j8==Vr=V1PluPt?p;;q6kl-0@D$@vJ<3 zySLv~)#OG|QTbgnD_;|OS#g=3m$dYqnJK?~i;8olV=VZTf}RAS-adX&iwwYxQ|*a7 z1VTzdhRY8`BdlS`!PAIvVZ5Sd8Jw-C~8$+&cXZaA`%@w{c6W}nvmxCASFEoNWpKwH;|EG5kMJ_r@&&Eiqs)% z?qOyZwtXUi33ymf-u`?KLJR>Ewcyd;qKo`p^=28{+nW>#kA$Dfl12~8@IH6*$bLZf z?&=Av%Y-Fk7(rIJQ(OH`%dP!5`NO8xvjc`Fcb`D=3wLGk+wcj^3mB=v@J-ysgnn7Y zMHUvq(pTB7642qlWylJ9FrbVCTNs*U-YV%*eBYfifb3)2(;?wAl@krp$9HdT1PV)$ zFp$43Y>t(hvW0_uPJ~0xSPCKseEFPj>>1`kZbe7+fchIt~e#npc-95tpn^f~RhDfBMZ}58Z zGw~RuP-5T#*4KPhmWcti5J)l#wX0~DIrWQ`2wgb1I@xGqBX0Jjk!>q1Y?w zTZPC&Z{Z>Diumax$N3$CQgO_*O?(uQn|dkKU!-|mUxe6JglolB;vkQ=g1d}ffEfs< zIR?Y@naPI$S{HjI;wm1kt0k4X>Zp@vptmvtdM4 zG-KBi9>0@=Q*k=*aTxBKuWz)#zK)wb#*V`25@3@csc(|j;@!+{*)tAnVHh6)OowF9YzBB#y=ql z{UOjfKir^CbR#3pj}e$WFlAb2;C1L&&e!F@4tofYZSH6cXuet`P{vO?-;cP{M#bO> z&;V?~n(5kys$DcquK*gX^-sEPWRwDVOCCS-bR?&=UzVPXFn-h2Wy(Spy3 zgEOuYz1i_)q`%Nb1)bjXkg1FPrF)3>#WhLBCkoZz zeOJn8$EGGKD9a1wy+uHvvY`B5toA)Td}Z@^J^jxkVRP?xvad?ZOXa(Ha>|hiY$^8d zmdef-o2!9dk zZ_T7PZf$+)%XHriJrWipfac`Xj=IqxSy{^pHcG=*`;sg`&ol5LpSgDMpS+}31@{lH zw2ts;@sQOHcX*ApFwjMag7r(%j(6UZe6m=43CZsuz~MJLurg$yi1Mj6@@5f88sd>< zcn1Or#5(N3^L@M`X~$-Cu%ACzzJSR8o%hYSX^!986!1iHHw0fDPC|oaH#=--p=zw` zu*J3wkA%eeBqumkD9Olb6LPYegYfwNVI=VzQIYLWJ`uB{&51)o4B`ds+qW6zBFB0<6eqzOBbKY#@SKBj@ zx^0%-_5p`8o&(cHHN6+DgHLghZsyusl>u6$xkjk{tve_a^NIh_JKxtPCLU_~8V)g9 zMP(M?*lOcT#X+_#K$4P#Ekk?SWIxBq%b+#_!T)W957t4}71G-gT*MxS1MHYk{WddQ zEWz5TsYqR7JY*$5F@jbC4_kz5+lA2?FbekrnAZ_Rq)EZV2pbW^dyAchD5TKs+fh1# znN?bI5~?m^MxQ8lM-7C8insYlXG1ft{lkr;xF`1yTxh*n06F$fp9IM>c~gB$xuIAN* z2X`4}UitxGXrw)<-?X`$sOBxep;q)X(VIfO4h=!rfNnk|A(fQt1 zSnlibo)o!6ZkaiD2e29xMrFXqr~|!R{=4+{jOUOijsM{E-Jn!PDl(vN?#N?#$RE^f zA2*NXsihu8R5WSmk&I{#o?KZY3h}?6+Ln;V84N7Iu#(>(5nTcN}HC2|I;vogX8YRPvK14kD{5x$UO}ckM@T^zN ziyLbT;yECvTZrMt*0y*LK`Da3Cs=>IyCqv(I49dF!|Q!CS;Z*kp*vL!E@mPUaYLlI zzPmp(5M(Ke0p(rLva^*1Rsa&rOv}Aw9PAHX&rXsd5-W_3dxSOaq0lvz69S0}*CU67wklS-c5IR1D{NIiln29F3&d%N> zO^AwN^yJZkcrM@dS;qKrC4}Xj#Et9dtV7nm3d!%;Ut(P8eNQ7MbaoU+6xT^dauzHV z=o(En?731AdV)`R3fpM6tsHZo!g*e8V4Z1FGrf;u|pk3~c|!Ku0!SzgYsd-9m*k!yFigd414 zgD(G*u+u(L^hxFG*9vVEzI(;^T?ts8h-#FIA~TLxzjY?A+u6d#`#BH&n1#RdqGI*uM(VDB?$IH+o6xUu4p5+@iN z5Mc+ZUMT^xyufwZSdV68<^pnaQT)riT0OQrHyNl1di3x}FuY`NYHPiB~y zFS*&+(T3k+UJ{TMVt`)L>0*tvG_!;@ZQ4z6%W2{p616d zEiFAFls>1F84giY z*C%o%^^W@@4$t%`F<}09$d~>poR9V0qg=qM(!`nud@r%~#&<6u`H^)h`a}qaNemsH zZvG;rcgjJAr{#+fiZYa?N?cJ1v`Lw5c(|4X)ZIA+9((PR8zVZIdPsraCMsD?^bQG> z4)CZYF~r^MNy&m+ z$Uc&puC@{o*oq=}3_=-JOfDH!I`c4~QF<)QcCReo|I4+Rrf5MI3-U;b=hL$sQUpgw zhwQA^Q{R+;@4qopw&SY&PDZx8!^24o-x8um7qL8(1LL%|aVJk2u<;a+i*&#}t|ZfV z$jM1aOp2tDZ-dWWJIP~ZWm5;!rE~tXtKoG8jBaH10@2iIOu=5cx-z5rYCF&it_?pguHQA z;x2(IIRcaa=hOu50Qtbm_iolZNdMj2wao>3XC7Zmj-|}1zObr0-{myZ>XzZ9-myfj z5-5Nw8bAN|rguBZK@|Ng?A)=aC{B;+W3VB2sATNzY6lYdGSy>BtZ37= z!tko&o!tk#%)&%P5)!?V%Fy6YEZrm36fAYwlE(-wog8%$p~P8p#&;I<AcWX1f*7W*R#Qz&;@HE^I!eNJOp1NN8Q3be>^r5-Mnod&0=pu1Yd|K zD3#A)WK;W6AWSD<#vhmbQ2p-9w}N;`aTYp?vjqy;PvpENyx#+)gq*ii5wZTv`}4tN z(%&QJ(BVw-ulRE?>}2GMK{kQJBSox%@6?80d92Q+2h1*DD=C3G6yw8;Vbm_ju+(As z#I#!I-u=VFnN~ZM$#bJvH9`{4X_0O^UtaC|eYyT&Hx{uu6B*9hx5wBjNY|;t8h-qO zb#NePbM}{#MdJ2E@O^$M5g*b38dMN@jL2g$)?#LW4W&&1f=1E#Ek|19F351i zpVoVb_w)YgJp|CMlKe<=nUG#dc7`@PkR79P8-Xk>n`L0B6xZ@34&2*^-zn%oB}(Q7 zs@4A+t#}(pa_=LpIKWPum>a*3b^Nl;Hb6@D@kGl{G`w3rAh#qnho4ptQzTH`)qlvsJ-=$wpy# z&#;Y?7OB8{FIE$h|5ThHj8_bm?8o6#+y8BAQ0hkO^6-#}_)Ru^|Fs|pww?(CE!pcU|dadAEgQXa}|vBrkS5w(r^s9Lg2s;FW@^HtwZ`_(A;H6X&I zQjM;-N>?}AP7Gh5VT0P`=HjP8O^fYeD7Ae+Wdp5i(P-((by@KXJq`g;TW1cvx&z0K>uRrgk`%lgVky4dhB6NX55IQTPB5ev(yrb!0aiu+J-;B_&AViuJ>by>XZd+=3tvMc^8cM+)UHi;7}D_<3m zmHYe&x&NxnVJ*QjDkkE`*|G&&h+O0){q)wBoM~O%|x|klpqr;D=}(T+Jf(g54pmqX%6Q?-oYT0bRF)`f~HAD#rBTIi4gB0 zz=fj1s|cJPm#Jc5Qrb+~a?>JHQPF?eDx6ieXVV(JwBp{8FR!X!WJq}2Rgq)D79o0r z4_dz3w8-Ze&@QQ+Lak3z<>p~$Uuge4YOTtXL#`JwbevB$g{*EgW4jQt;fjh9Uj>qJ zy^uZ<178-LkdtsBi#Js*V*s=&gq@Z_5qRA0_3PTGuF}(=FSV97AunBwwH9#|zhvDa z6my@;5EBNY3zP;(u{m7FfUZ7n7MMA=Fj&4mzWmgd%g=j8*woBK^3+l?_yp{<&uNj5 z7_~=~3B?1gD){1!e(RP65*59(Ao{POv*27@#C6&uVS77atwxym3k38F3@9chqjHj} z5yktTa=c@h(0b3DpG8(akr+%cO;szAd5G{M=KaGVMoY`bGxmAJJjPM$I}iIZ1x^r5 zy@a`SR40^D+k9-QKh+l&K;}B51n+z;g0Ng{h`Q%4p$-ua8P(?A!b7faFkE`?$=z`R zrF?VN)2~)hQMnfitT_?8|Bd@s&W~M!B9bxIH|rz4o=b@!_}qpv0{`63!RINZ7vsX< zd~I&K^Otk}C$ z2SI8$X1G`?%}W<1-7E8>5NA45r&u9_B$pVmCbamiG9Z?|lezpYx-~X`fMlZW-JpAN z;=KElcJIOD&ogPOrMFdh+jD=qVi5y5@%*wh>a-arb zP+U^P9b9j{XQCV#NdvlIU7Y`0=P#=rL+XdHrS2QDso*=Zi6N5ZDlCY3co@4AWnSfi z<{&#M8HHN4P?mJBX1X_)6@keWCst`)o&B5IOtfkqaCsG{`O#4?p)B0(l)u7gshR^D z*dzuMA=Xe;)EF3PJfxe5Guji%yuK8UpqvW3418@FpkwqqLVF`}|J-rWwG+E^Yc7bVhlC;Z=5iq=;{N!R)iQ zv478r2{7)5@JWmN^hq#I)kJdZy>$mD7(%#-V?W@UaMBfnSqyBbdbbOYo77_h`VMf( zCFVqCIltdtAtO0B38v>`>4lp z_XJAF0(+>-lRc!BCL!kMH-4}(AgTJf-{)GK^(#jY@Q`B6xMco;eu-1}0HnA7zbPY- z04g+FJGt#2B*Bp~ZM*DZduIpywK}?=j7pSydM5V@BVLn+5HBfaM7Eg$2skzlH-u`s z%F^8`zE_o0rMvrTN?yV1(j|`Y4O&ulc`G~@H=!khEnu!KWuhUL5{2ql)8F9SUq<- z1gP8_x%j>oxNJjo4D9^KUz=nguCEw3M!f@cwUb3iVi{XO@)3XuwY1a)<(r1h>z}$B-yDAnXS879f9p9RJw2h-vYi?shA;~YJDQfZRqTd_cuewd9mA{}I<0TNwJ5-eBukn144+3I zqw}s5?N3qBdwcOoGe)0oWABnl9p3Bsz0&LMT*qS)vvDAGW9^BpsUNZa*@OT*^!w&g z2%~m_E(@s0kL}~K89{;UA@jH6dyMM%&V&S=e=|^-RR}VCn1<`d`^|jN zyPU-B)tWF+5{-W3M84FrjQxr{bvbMV?L+_ugVSIe5AYFRqz)1z-k*wr>^7NXuTbio zsH10N!zEcn>BtXBG|j|YhnQ)WWn`B_`_$-s!a z^gg)7zk2Z*q{a-hP5BFd5h)^wgsoqwc8xWTR%||#n0yll`9&=Z0pzWKjGDI7!DVZ^ zds<^~+tx|mb>i;RMP06J?<0d%9OR)kpWfSyH=P6r=5De^Y1JSwQ=FZT$vML1EJirl z88+6VYP4QJ_J=heuM+y||8IF9 z6JEe(MTf_;4YUn!7JjK9v>TA&C6?hpu1Iz6y1n|Cl;ejG!e`I}9fiNxO)_G+2OK5A zZx!V*jqkLq*XLsgPe<58VRnukgY0I4e1vk}49O7fX7>zom;DRO$S|QL_i4$_y3`(w zYwCuN(cmIEIc2wNTT_DdYx|qRwa7|2iKBv33)}JmZiMRZcm706HHe59^kdG-E+y0t z$VZ0*UzO#R^oIp=Umm8jK4(uUk-B(D+6FFJKBQ9<@bhynDffx4b+2CA>BO~w=%;=9 z`S7N&DD~g)$4?AcL`Ti7hL&>+Ajbk3D(!CJQtf zfgdU&!+B*|ES+fX&TRu|lF)sKDFA4Z(eVhDPM8W-prV;75%llr-=*c4F?1Y>mc zgU&$#?7PIEQ5EiTangqCrpk?jH1?LWxbR3zI9M+K^qjTAm2KNHMM%ZJp^}ua1=2>j z=T$~jq~BL87rE>6iIwo)69M`=C}8q+VN6tR@m;fpLOLqj$2=g_ib^IR%u%De|0@+3 z;l8uL{9g`3B_Y9HEWV3&O>4pSEgzcz`gam+nqLJb>4C( zl=DFX*;aggeZooeJza_TuA{scwFEE*SOwpWdeT$Zo*6 z2$7P5=l10<3L|_v^$L{BC*@MsG2U&3Pr-k`9{1SXUE4RT!1~qF;JdezNdAL7vU%pj z>DtOxY%;2lGtT6O%48RW`ji3Hw6xP%PA;~lMn_txUqj4pRC`&|MrqB}z<~PnIY`fs zVX3bse+c>nua70;fHwH9wh=xJXo`XOB2K6|GQS?W#o9Z~Y2C~Gkzp-LmuxS;R0XF? zpap^%Xol1I1Y0o&FE8OzzNBGZj5& zlMD*z`y3)AgM+NA&j;sU-*ZXj0;3)reEn?wz6b)`wGm6r$^e>&YyFcE z@`+?&ToR+-p7u05clapcrW*n8Z-u-9T-#g)3{`$OFYF^8k*)L| zjWb*&(uu=Gr4g3{^h@cd)j78vs$RNeX=JTUCW$bUlfci{3ldq#y}&h6PNUxrz?jef zlIhKs1~TBxhl3;cds0>!0^=-%@bSa>c-cQ)*43F}Gr*K3O@r?_7v5;@%ksE8@LMI^ zTOfP-^u_uH4pKF(#W|H2p)$}C(k#PUu$8w0VMFf=Ofn(p?~f(`$P3y3t??A$$Z3x$ zB!QDRylb^a9%R&M;vCTHA2%1rDa%%iURrXGBC%L+T!m zqO}x%0duT2L4fr-IDD#zx82Wc-<BHX~q-@tDDXyw~)T_kV{%G7$+yT1TYe(MC zU)z&%aNiBDBdskQE&L#U^l{IfG zv(wl3be*5Yfe%x}*4qu={8Ji#$*1ohLY0-@g06-c47EdPt;-s(C7ZmD@<##t`^0Sf zi;P@cgF9ndoxycHTjuA_FKFPLqBHwH1%%wWbHElK-^6wi&wQ}I<$qcLIH9M2ZBp;P z%4wZzpKML-!^6oaj{U;{n+!+IN1-*tePl(d8`!g^@1oZ)KeL>y(-q}!l7OfyuwOOu zb}%mz1Q7bp<4Vxb*r${bg3)kPHDsYXY+K){)z%m=s+*n>5lb}5+U)Efr__-vtK=I^ z6x5kLZ$+6TNCzKVCL_LGnDi|QB7TDPA+?YL$T$yOC0WJROIv%a=|43@6$*( z-3*dwUO;-s1(tna!3lSZDr@^aR^@&azGbo%vIg5@L{U5}+;X1(AOUQxEWI7-lMoY! za@f!M{zC7R<=Wb@AM_tn5H zI5jS=rVF>Zl((r0Wk+s>ARC#bU=u6KvPdsrV@RI`#yb=WvSAob+*@wk%RW0pV zC#q-GLeS-X4g@nAHifWB$%n=1!>tMbD?(U^{}kN~dBvwe6oy1?$sKs4?xfZwj%;6X zje*7f-GsdhCVVuP1c)N65C{$Z`!oJ%?TMdJhT$6>3=l2M;4S>;>Xcs4T-Wb_m#^18H7*3MeoM z-@@zXdTD;nlgvr8W~$44OjaV6({>>Xt37_I!lE!k+396L?_<3=6lN?@fv_)a;uwTV zN+Su=!u7USdjZr@FKiV+Kb_+NiRDR`?uUrG)4+6peasGYGE$p%G`rl`gL^oRW<>f;jx-`7(5Ok9$?CMl8>9uf$0cf`6Vo(MIv0%xYCxa7Vu; z4rzr=$o_vsI#JEy#z&N=xW6(QWm08trtN@T_-vPE`rrq!9Tk0blMv zNQPM0^(|F5u85kczE+6FTyJ>rjXqK<80M5wkoPjV*&Q6}NNX!16&c9qyOz7Gu!!o& z(GqyNOztHs>^BDfaRtgI4QdB#KLfC|SAq7GrgW!IAC^7xq@@vg)JpUDb9&!1`@-ZB zO=R~Sk3k;@MQai^2?GBpLej9Xyb}4&l%@3cjz< zWj)$_I_${F{K+EhbEs;sd5DS9yU$MYZ%>B>%4A<(PhKCgu@f48ejHai|21Mssj5UA z%-a@Nm3c^FjOeW$9lu)A2_T^mI>3&Iy8UyC*>P>OIYQL>Cm=&q-C|BKi9*0bA2>@w zVLdt_CWe`?RQ(cZ+w)qE@v z^!j>lrLC+!vYik~PWyNZ^#^utJ|2VNv)uob3(Cw#Ycb@#li(9n`Jw(>Y_hBr-Myl`bF!jh*vE8t zFO0Q6K5PM%>p)GmH?zWT9>br4M@CgjGHPkfe)8(8heGlBD+YjVA_3LXY#JHrD>>Wd|Rmz!@ ze>Py68;P%5=^QUA%ce$Cg)Fps{x0%V?_VDmLF`jdzln0pHXs08>v~sdw2Q4gq^w)a zCsDv1UZ0$Ate?IL#y_W8lB<3ZO$wd(<)C^SY^;w83V*Oc$mq(6lXY!NkR(=`OM=aw z9{g|=>Tpxk(*p^-e9K~{3vvcm=vfLE|LER{fio=E{;h2svuCJ{tZ#(HV5YgnjLCzG z+Yh8G-HKJCIoW>pS2XpG#C7anGj!!5MSi#?P7=e4CuKFB;M(=ca`QYiL%P4N&B)u} z*w`SSJbMB|fN4OL_*W^S%>2<`fS5mkApP$IWx+xlr4}SPX_{_i^s#|4kw|tz1f27H zlZD>-Tine<(+1d0_oClpCsfc^|AnB&pKKn+DOz}m3UA)Kt9JuV+Kwe$0?bg5vZ~S{ zSq%V&CQFv>MIyDT{ANh3tR0Z)cuEPCufYbH4dF3n>{KGrUfxX6|Ln++EQ2dcdzvN3 z>EyTjOW~JDz-a%NvRWKw8n83v5=zjP@Y;rF3n-Z|yfkkv?FMbGj}wYUZoxX%U#>%> zNe_cGt&i7UPy-pFo5r^L2oT{6&Squ2kr}n<*d5K`^%|oLF)^d{$io%&!5NC-4jon2 zwtAnJ5R-)G(Wm`=76A$P{2wDGaNy2kN9weFHVM$6!>adKsoy{{zN@}m`D)2AM*0fTL`soQ25Kpka zL}F&X6$30m%mH1Nvk}FkO^=@z$efZn5Vg9FFIFs&E3y5z3Je9JFrTF6--)UCT5tGXB}0e+FdBd?IZBs4-CXc{TOCyZd|2-IAlxOp#!)AJyQj zAC`4_sRn0}mL-+gGnf>h2{CAjIVnC{c zTjFUu&(wrPHQmRcP6_l@1Dx3wkD~g)Cg*Y1&4{YG=UO3~)h-o{xiX`V%yc`Q=LCN} znf?2PA!*%K=*|&wr(gmJFKY-iiB+2L*bdQLXSa~RqVgYRTYwMph}drxHII%V2naWu z5xPml8;sAe_vxpejw&>=zow9Q_rc-8|4C>XWnKS|hn+be_Y zs67opqZ@7(r@IXrMCp^rs^6`}OtOLx$JX{HiLu3wm{h}b3uOO2b{UbaX_rtJYYO+n z0C$`wo@)>W+{@dol^vlYy<8A-I$N%HXY6I&@mSS`h)B#TKU!P(*$>Zp>7s$L+M}qh z{`FQjA>_eu(ebdXM)g#sTlun#(gQmoSrKV-Kxta|WspqGK0z#3`*UD7L>dYE_HBjU z7mo4r=C-hYGAre*%^L!iDR%I;d25C|pU`abY z5CcrhU>yIa+Wk6QX9cP4a-puRI5MU$C95+sj4CEOcrFX1dZIb09Q(mO-AEX(KN%u| z&I=7JmFRtU-#3S`<>ZvL>FD@1kKiBuuws47kyA`kI3b7)e{V2>tCS$OQyP&+P-!=2 z*)TjT3qTbq?vTWMt=XiBt6ZywCQCO{A;S(p2@z*ytvJ4XFVNyZgw+ogX84*6o?Z3~ zj@ATze1_DTn|mbei2%$+zO%DVBDdptyhXGwVkwa(M0X31W@<(t=&d$GM~uHI>cs&O z_l+Y`pCm-a#rhEe_J+`Li+9Mv^|`_4^R&A=HMRV)eO|NkFAtzKyZB$j+nTpWZ7QpJ z@1+gD*aA_AS^==>jfi;kJNZYJ9wz~B466dYg%CCQ5(j6+ zzlJeU!rSp=S5piYmkU@XL6 zL){gtWK2{wt)9nw_AYE;96wD36z{i3&;3^(44+B`OtnAB4yD^f0gxN~lQrg_5zvsl zdiOtdQ{qR$gqYj2Qi$(jv9V^hyh21ULM=`H1Hil-9AU^x%zveGA7nJL4RAED^hi)E z64y4sJYzT0SLw2Zqup_HP=DEKPpoieHE=7&{iLF@lK`P8y#o4h#XrMfDB;)srK-$t zp*Q~llPU2O8Tcjg?Uvt#lrVdy!p?RO+-jk}`1WCQN$%6Wa+#Vgy4epJfsQY}WSa3{ zyf0ZS8=snaYm}6OlolBgsVjhZ%XPth2{D92^vx4g)PwHcHNBJ#RIx#tom%O*P^B+@ zp9yX*2!TP17?9;HVrg9o&HlKriWC%%t}?Qz9-q52XX2T}tdt{o2;6vxlb#e5Sz*Bq@p)Ylxft(b0_pt{tx&!)~G37jl!QV>k78T*mS)?OY5OoSgDh6FebM$3P&1 zjEbx>en&USN@NgYfRo3?*>Kr<|6*SF)#F%VvLb^j4zQ$Z;IMqItAfrBk|+^OOQ+(K zNJTe05iypRV4#Zi#v|d_-NamPO;;h*I}!US{p{>JbhBIyHa$}(MZM~9e9O1U=&gR# z30o@UMvrg8Lu5urQJ{wPyfbb7^$CMiX0v8%$Khcn?tHewKvf)h_^-5>P!G)SFV@qH zt2(=M8Xi4()r z3oEgae>u1VL6O=MZXe2@twgH8vIh3w6sbK`>a7?R@;{&sXSV3H#>QrV2zVy8pFO{s z&y}PqeN&P)$Z6?)V6u48KDf(PWty#k_gA#Mz;LqQx#W5SD&gG?;0{Wf^x#JphnFm& zO*hR}SJ@0C~Jn&nzw+(MyH!y&n5VsQaOO1L!zTe8^h0LHdo zNC+!$c&eV0RM9`Fzf{7z8kIJJ4y6Ojjyz%sk4Q8gezbUfH5<}y(R zFC4=U_e3HB;Iicv1IZo<@m#5>*n~oaJlp#U=33q*X`JAFPyFXU`Cx2pT-4*M53tTl zIWKDvD)4GFp}RMimh(KCNLM$Ljorb;hZY=bw2Xs;4;HW@w+L~Xy*%`cA@vt&p-L#? zwVf7%AOo?*D+LfiaR2fV5?O0!V5c;9V|}FsSlon+0JqfQM7; zo%{H?fY+vO!DHCLQOkV#P zT!?_3Q36jcA2MlvkT{@gqWFZ1+c4zl?anlxr#xT-Sa(Z7GuhaI!=#{o-s7lM-bSMl znw;+m>hHp!{o#5npazmVRhPZldc)(lPhUE>H;DLj51XE0OdzB#2=1Tv`}iA&B|R|l zj3W~tv)E2YhnbW_Jsr(eDD~WUx-}muuema!7qXx(^3!+r6o62>?_oQWhU@gc*9|c3 zXHl=NC(C%m87S4QdUpd4yEpsUl;ZQhl(YB=R=scUjRvP}yEKHM5&@=2YSA}FmAU@K z#$Iu2UX^%;YT86oih6T+S66N?p8_eBdat8--fMlCFdW_D2NMsJBSVO?cdf(bjDR-9 z=lVfJ1h@pazW=bl6R0Ccd8`NJ5&F@DOZl01Y>N-LPcs+(NCr{giKX1M>>iZgH#4D& z3GKwg@xbAOYv*kS34~zF(yQ{rTrAq(_nnnJbOm9-i=+w&^j_C()U&G$Gm(AJftLG< z&~y56X$Q4SpV4b#7V5{5TUyRse*m~4hx8xE!28L+9`?xwqHk(*C$O<$00a_yJF?vc zEe3(Fb#*rts+yW0a#L|&P$pId5VEJ5MM3Su33&}DaR>02D35Uxz$9-t`(M+(8ov@Q z)Oy7gLd9FQ{AI*D=!~_gNT6uC<@rIfcBv-k%zQIMdyyAY1^ByE8k*!ftfmuZxxsC8 z3>7P?lY8Wg;&Chr(c6zy6Luy9U^^=;tksUH(PscK3znxz zz?h_;eET-8LPv3I7pyl&Jw1)+{1#S=Weyg^?hm4j>@mPZH{O&bH1uZ^K!U@k!5btA z@jMi%RqMcyYfLp~Dqy>^teTduzF(>d#s3d5*(RqYz3Ssxp|!L7u;?1H5Q=&|pluj+ z85VpKapWp^P@vdg zBA7aV5W^@Gs~l^Nk_s5qbdfaLyI@ToB6uhuu z`n)%)@#+u|5H>bwltuohyd^Ro@7|)tvcZ3H%9b!%>UJKW>v?pghC!$8?d333`sC?- zPvG!re}DU!XA|AUz=dIR(&mxq`R(qqr}wPumMj5ReCXTJhCc&nKHuTH?0oNas<$iR zQU&Pi|3TgvqV96=RDIs*K}#HsVP;mUjBT90sqye`1{L5 z5i8Wpiva6I@G%+wu%QqI6%`Re%q6qlYr&LiFQ{G$LV!;*_wB~kmaO53uAi565xf+c zOczX#GFL4Ypa82OXc>qCI_k-s*LkW)U@`Yi-h2b*Lm}x!%VaGD-yBPC*V+)pxhR=~ zVG2PM9Ejf5usbO@|LJK_DXtKcz(5EljQi?}^_7Fv1(*xg+@GLAjhsb3HPzq=RRrH( z;@{)@w4Q1tE#LNc?$&nF1UIbdlEje3P)q%C$r$H^{-*_yE-w=Fr~G8P;LCq(&q1<;NEwKK=?6nv9K&xHE1^z<7>aJ}-8!bY;+t&b9GsXTl5 zxipod^QYMyv8vS3^`3#tkCk7i^>$V-daw};P<>&>!0omYuSnn;W)ca9{O3~|;vVh} zO}IcFf&VJ%cGsETm5sg9Vt*xjO$T8-S5ME<%Q1czz^}wxIBdp>*=Yc^ygdJwnIcHB zxCUlId3q2P1eGu`lx=>iX~4?=I=}@3&~iya+w%0y?u#?1ji23f4#sqtSbYRA5` zlzc#mf8c}lgL&3EIQTcu>{q!A1)$|)X3o#{@O-@^b%Bk|S4r=^0VJ|*->>d8^7?n| zXJuXbuztDB)^Jj?*VZZ_pHJ&AI&bxnx%14oXx&RTHZDoP*k&zRQh*4c$C|asqGtYpQ-_MD(q(H`Ti zf0vw|f`iG>I`D)1AR8FRj@`Y?pX)n~KGP*q4U086??zP4gnRPlY1h}->Yq7kiCfS0 z$f0fgzs@QyzR$d60yq$g2I=`VCc^Fd=?#!r1O4LX{gAH!n$zlaG^15q5&+tgVpLTg zFoM&ARfIx%DmGYk+U4;KGtHYw_K+5FIr0Gzud9{yp^Pp$3Xa3~9k4fzEJ6NEr0#lj-WAt&N{N z3)vWOG&KHokLq%j$KOZ}KgX2RYJ-282(+p@Q>n~&Z6CowF-SY9=cc@W;L)g5%={$fWPm|R{Dmb-_!Lo#r~ht+|Z_RVY6v7 zJX(2U5pPQ*@VI`1s`^*1YGH97)Z!`%^iZ-a>b{OGPZX83ocTF4fKE8R>;oW6h*i`4 z>O1X;pH{rS>G)|T9@PgOsAT`7Ob=k*vN6e9x3$Jlq$$k%gG1ic!!HkjYy~%c&`vsr zauS${?{9*85)ZGoj{R%bCb_$)wKPJqN!x&yI)K>RL^t*L2IT76l~e$tbZ3&!F@x=r zU+#H9*uoI2*$5NBQgoFydP{)bi+yeZfwsUizZ>IoDnX+(avQ+C4U)9h& z7kFZAz-;xSygU;;dAooY=sniwVxA?@1k=8*EC1MkoJ(wUQt&w#{#0;s9e`kl?uc2S zQgJ`&6~Tvs54yo9sKnMwX(KN$nX=Ta6%oTWVwMmsKqjL(5xx^Jm@27l?VlJxF3$hQ z)PK<;v=CzA+U`?OE%mx>_2LZ0qXf@GQnD#N+nN^_*RM%p=b!X6Ij_S3cuxVt!ow7x z9dZi-pPGOJa>rOGYRduiq7i&;afJCm>o>JKWt?ZL-&lr0v%u*FCi{FD_)?&jkN*bA zE8WW_Y?{mFt~lme8&b|AX3NHET<@sc+re6(jo#n-DvHG502vCn`}-g%hBrsZMFluy z$hCk{VX8OWcc3`nJHn%@i3$Yz3mfT0?|z}`n}pywmkd*#u~a#-;Fp>i@Ta$mAO-KM5GCUUCk?RZ^%Hrg0-Jt$=$~D^zKu@Oolr_f>b0+ut81<@|Cg_!%cNXrJP5!s6n9Hcp*O z_+4r=R*Jt@YHB2}FoGTtsr_K>IN4T(^8`KXa_s69S1-A$u$_vCFsHXN`jN{@Pz#KW zz+_jTS95U(34kI%ymN>UlDLN=1ZYc~V&G%#zO)cR@c@Y%#X#{Udmz#kV&JkUE?>uO z^ynl#*g@-Z)26p#MvYM@bJ@w)Rt|Ra9~_0o%q$N!6oA~KclDXt--aw+Td-UY;!H~n zGoypRh(pj>YvP+Vah{@j7&lwCT7nHhT^8A6-{ zR!-HDZe@gZo~XPJz2Qo%KhZq-_7{=@;Qr}3M;aU&))>2%x_=*k)L5PBS68x_$?sv->65 zxc&DTbkSaxzP>4`adHfeo-2?6Q5C1vGu56!ezI0`9p^IirGiQo_|llVsk0_3pP~`{ zwT`aXO-FztKpL^<5Ry>t)Oy>@u5<)Kq8$*pDqlV+rI)ZYWo&K_dO9`x>G9#Keg(3q z+aBo^(%Y?I?vohv{J2u8QEjt$sc%=OqrL$L)Ra01^Pq??cWwlj{MV@dC4N3+Qj|U$ zYEYt;JsjE>^a8FfD6I<-h;EUTe8AyD?e?1&3+Q_S+86DKwID{^sF`w{n^K_9)G}~i zhs^$rvV=~Cc&8(@nw_T_r`pmq@0e{ySoFB+(iw4s_KoZm!=dt!f9(x*HoUA@AUK$HZGY`MD+z-DCSh&+2N{g~g!utH9Hf z@zK+7vM!cLX%Q~e@R_P^|3Z>_${1M%uoo;|xYG(94`>}yv?xUZ5WA~cKIr=>(81pA zfR-g$)9p7wU4@;%F1Y<=sb2h5T0%ht&rOyFa!WH=bK%rxeT^2h#$%KP(3{6Co%k5F z84~(%4s(L5rAtk$iT#J{$PYxEv!1*=qMP1R<1!2#C1vO(`&ZSb!a_uJl4O31R3D!k zG#3zGL<=}*5|YfZfa)swtvRAqF#?Z!(oY4a?F}INhx@*MkKm(>g8U7n6 zqz^q;{>f61?bYAypF}Y=QASr+w`b%wKX8$t5?T9sc&X-(O;EY(oCUP86s#+2$HP$u z)isLkz*N%TuQ}_!M{idalP91g0U+Fp(J%Dlg!<+*=`}Uj=QND`z`OIdzRZ*iY%U*1 zU-;NP2i%LDL@;k(tM92mEEG!tsnlnDDwJAntl-kpotgYRzcpK8wo^t>`Mr!rv%k|5 zga^Ma3|cZ83G^r36Ga(`+lusCrC}!Kbp2$}F)UpNr81+Ao4(#cgcM(;R^Q_jO8vzO zr+25U9SBk)r}LTp`_{ippLE-G zXIw7nrK}iyYvo$_C?aP<869otuavqV_qh*w_+cL(r*#D>HvQKk)lqz9<-P>0+_4RGRgJmqIVdWMCG6DS((iV@X?L2MaqJuc;c9M7gOrq%E36K>29*(nAFo!yVE>4gu$;`*km6$N9EB}Rcz~Fc z>+7H8*I<1Df|mn0rctHp({awMWMWEdx{F~7FO=jdH=nJRfH+6O9r42e5DX+~Ed9U9 zGUDHx!RvUpGWmWsn5)+H2mNuj>xFH05{9@V_?_F@t8LUOXsv&spBWk9*Y0{N6g3bd z-VW{%jDL3FYB39Vl)ik*zLXN2e5k_C8mW47U$l|;0#*F6k zx`oOwlGxH;s>i{S7=O3(OS*w5sJH?dYxNgr?T_>F!e zg#^q=O(0}v6e}zY$iW=AfO^e1hNu_&Msj+_YaO^qLKY^9Qs%u}JAw2QYV~03x2SNE z3c`CE-MKd#^XhjGuy|9tZ2jQlY@~+Uj)vzx2l(Q(*JC2K#32{(L>9JZC>tB5q`}2Y zRs4zHWWlWc&s?3*`B%j4oSgx@E4fo<)e^TQ*`2${Kuc6%j&Fo6rps72S2MG=B0DVj zy;9x80~2rM%wg+>K79K>7*~9Im$3CvD#~?%)fKFFZJxg{LP)EJGoF;x00Qd>zhHyLj9O!>}EIm~Awr-YiZ^q*1j|@NOJ-yrUNJc^cNAdb;7^5s)sA(&LvTS{&KF#){1eS(G%@U+r>)nU*ilFMW! zgMf`uHH=L8wDXII>-~`m8|xx62iQ_T58+G;l~47Mdlr%TN~ z<~C%3ahSL2y+rT9HYM<{y9IAaEGaG~zW{C`c{g)v3e2c5sI7~7+DA{8G&4-Nu(OLn5TrU%l>Y!$kc##Y)eLFA1yz zpW&Vc9u&U&o-ZrUuP^ScB}L9Xe-NU!FA{v&@iBS z=;_Y)_4$F$F&w|WCDMRIr9KS$Rt9n65PK1drp$#bA_Ec_!qH{^9}{Z-`Gf@i>G55I z&}ybBJ9~$3VtoKqS9g^(_1E&lfbfaL~)iBWeyhJLRjc_qXzfGNsKdKXdu)!=mca^h-77vQ^}-)=bL`T zB%W8Y@M(RJz1YjmKmf~;;yUU2qc5jMBv@T-fQBfBR0-8=*M7R*^9A>Y`2pNInyNe3D1r>=8*ja2rf~6g~6m!af_W~6m0O0v=;(7#N+dlITTjWN@?mzW)QR};s2{Tf1Br5@37iguIowY){HM60jWxxuA*pa>< zp6jIuKFrW3@f3*L9sbS%wx&wxY7eYFBS;Q%L-Maxp9IaY&phs!64uMeZ-S0G9V6dhsv2Y7_CCbbmj$-7{TjS;&0y5Ji&9wioM z%ddA$ii(==Kkd@%8&VuZPJ@U<-n*<5bHgYNj}i=oM+l(QqI+N!;*v|?1O#X5>JbFg2Wx&69p8ttHI>6##NNesGpc_B-Y0nmp>NtK2+b(OKCs8R|0`=zG zb|1)W!dleBx+EgU0*r_ROC(Z-(q$ZhpRsyu6kFOR;fioOR`jLl11u@}EK~$KTR#uVuH#5zePPe1Jq0*#GiP+Ja#AKnH;|vW# zd%GQr2PNvF>AnYNKJ5^o)Y=>s;;Ug}m3c4_E#qPjJIcZdSuNrs?iLe&8xx;jZp}HGh&;Qm*!WbtbvD>FPguUG zgW%BhbxplMA+61mA$M-)d1k^G2D9n-N;ks!W~ zRiHt)fcBW`ZSG&~zzcdKfwbRr>b0s8ysLucEkUKTb6FlS8C6#T=sEunlA!c-`LFtmoY-GLNnA|ESNV;50hlQQ4-3R; zh1cBW(XQAMi3V{(7PiY^z*h~KI30^I3GTeSar>*LvR8it;;xfz^=t9Gnrk8zwPM_i ze|=KZA^@Bis)tg7r32_bQ6flq(AS_K|4TPw9(U3e4ecmrV`D;rJ4M;b3@oMe=)rCA zqNL(WGky*^$@`N6D@yn(!^paJe1-`x*bESE+qhXnW9E8|%v~JpeD9_iYd^HqlvMsp zh=cC6v2jkz#sxO^?oHoA#PuhyuRFC+B>&(>l$VYKPCW;Y#4LC zRgn`}g!>7^#bp8!+}e_?#+{%e?R!!i8(#KVPS(oZj&#VQ!i18i6G|G;BW94ID{>MQ zC4ZJnRz}rk*52m?1ovgeMBYG~mx^ym5`!exX>6{dl4UxMj$V2;B4~yM{q~g8dtM!z zbVY0f-a0X3Yl=|L!XxiqMbcCNmS4}qf~M|FpIKmd3`9$8=n4l*tE(NgTL zrOcx+BZ;LZgY$b zY-5^W9?c>8*(u=(^k4J{xZc(W0`d4oo(7zF5OI}M$L};&dUvHjW0t$v9yY%fMYJRi zi)ta7FDaDAk^QU6`1`0*m&}qvkrq`7Iy>#__ZFjV$7b+h<;V5;5It=)g0Cy|cI=6s zMuAZS``GZg`ThMcd`ql@Dlw;x`V zluT8us`g$N-gPH}U^wn{e(?kw!hO5K-f&~!QGcoXeb@3#F>VLw z2NWPJ_tx1mE?zp;W3)hb#>fa0I7|L4wYaP4LDSwa)!WivA*10es0#X25Cz%s^{B3P zDjE`^ST!@#UtFao9VJ)AH8o7B-LzPizglehbzeJ^h zYGdt*0S#QQ>dTv=JorXbl@SRy2=Kro>3JB;dh&by;|*r$?rtnT%y~JU(xL=V3x!&j zrSnHeoLBYIJ&~CX0Tqjpx`^2TI4}`UY7nSX%e6H*s|>>?bo#4o(RSPF0zc1Nd+ER@ z^GFeqKYtGINv<|Ugm7Dzz!)Z9)2RnHUOqYhxK!FmvPRPhc|)g`hbQ^21ja&z3U(-V zYYg&)EZC$M(64w8S9l~&(i@uC7^OGw(U*Fv+kzH1;Dd4bjzQnJsLv>Lkf3t1Wapyt z`kI%lqzrb)2OheskZ{|w-ge8CE%AJAaL~yfNV+@RQltmib&vo^M%#F_zXAWWW|>s` zN&$YF=i3q0ulN!)bcc8x_6uN^p&JlBLpg>pQ;K52L)Z74>u^5ttQUtt2~+(uJ!u*M zq?o5{!9c5~H#kPtdL)Nf22fRm;xVe{q*SGm{Wee^V25l(Mm>NK_vQYKwm48$k?Q3; zKko)mMAh`HE)l|z7!cwT?)M*u8+5c?1bHUKb~1MVvU+k|h=c@mFm3HbTC94ov4PJ$ ztiYyx40gb-MpzDV=(ubGM)CCI;XQB5YaS!(U^ibsa^3I$pn4=oqA9(Pqe7l9E|o7T zd(uYH4lLZpOwx2ElBTB2t~E7^b=PMOr??#GViM!B+;?RQU4VQrb}5kI)+Q(aBI9FG z;Mz`3t0=wQX| zhDo+qkQEa}KDDtm+PLW`!21tFa(q@ep2rs*klaeIZ&bkn<^SzZQ|Cg1qm$FG^)`({ zKwj!7q#QBj%MAPPHy$*Z8}FIXZz)Ny)c(Q3^T7MrgsbQ!8(rI}=#UPj9HEm)Q+_km zGcK#q$dzOCgJ2IN)l=x0+ghVM9Qh~#Q_qXv`a}u??} z66I_1M_`JH1MH8+M}$x}>}AbASG)Qaho=wk=}*Ak!uCUj7~U+mKON^|takiGzi1y) zP!jrIJ0zjg3Hr!j2|Ufqk45?gWQ_iwT$f2s;#^|~D|AVRSEpR9n1f;mfG>tZ?;8!T zsQt3mUMTj8X37wf*m=%kKqZKqT_TN*lxDRkdgkRDv*1M}j|5PWg}~bLzd3XW#^!GM z#>ejvgi!n=C=^v?;xId}zL0OQxSSvd`}GquDHW)W(fZu;cnr-A>X2qn zgl7Gk)fc})F+O)$ql+PN7w>L5=WXrFYTre8cm%r-kz#C>sCza$HzV-s zFV_$Bq6Sv!(+9!VALY^saCrqXiY~hu&h0ZH^|g}|dbz?d=zUpy!6e;0_cz%A4n%z6 zvF62h1P8U1mn&goNMU(6nsaI!tf4#qcT8Ogk9j~R&wI)3!w>@sG-^C3hSNEZG`2inon>iS>YA6kDRB1B@K zV&Ih3BEUx>sd{0W|DsXvrb(~5(Yt)wF}U$_)7;G5j9%5}8rG%*RgT5*CQ_33^jIGf zKcYOMOnvl7M)(uar?JC?`FEMa(7VTWo5OCwHA8!_;Y?2r+fo0tn?F*^5+1WjDU2-S zb5qu%U>ozv=^_jJ)tNS-!$<}}?&(Obdgl8ai5^cWp)@YW=5U*#vR=m)0#anfA$PO` zDnJo;{YhP0nKh$In-u%1!lDKF_HEw>j^VafeVp<5N&p1oJRui}r-r|hihCHfta#|_ z>`(wpGej55WCCuc9duzT(^J0%whLUc!d`Y6B(Xd|&~ks8?cH9_pR-+-B1D^-L820Q z9w8;rJD@Gn;8FY_{V7#L#}oS`{tQ!Zk&Z*#^fJj;ZPslhCX_Ny}jZ~N8g zA&ihWoFOJA3rB?W{GzW6+Eehc2n}OG1^cP9KFY*fkPDFG!!UjInTQcT`77T$U3?gr zO7Zd&^EWftSO$!ubOngY*|f`^@zx(fEyzs`=m&UldU$adQx0Dz*ro;FWEU}wdL?bp z+covFuV`ou9xOKCriU%CmHsn0C}U{oH(J_Tlz`;Bh>FxpW;jY)W3|qC=N9d^sGzGM*Dvb@ui#0H;@AoUaYfa+VJ6-}&efv8 z{JB?lh66F74ny%EGsAd%`*GCHJ3XeK^~sYSRFC!kBpdv6LvLw3On8$ki`JWgCwSs| zm5yeRpNabbu)qB+NuXWc_CSE?t9ETKkqJgaWYTr=^UiBw8$pHN)38Jx9G(nTU+}mU6LwCf+=#o(3!{1OPq%p|BtG-4yyW# zx`*K+AgOeBgP?SGcQ=yKeQBhwAc%B#cT0zKcSz4f)Rl_XDL+5&jLqeRgqMzAxrD~qhm)UOOwj2M8rg>vE8`9x> zPV~*^D#?1_hc!}bpJWB3TdTmTjc3!%%GeM^2Ei}}#?590dY>E&5&CpEeQ)aajuCZg z=m)~%hHDeHcH&zms=NCY!nJt?hLch>zbsTPO);aOblaAwx30>aUCwpK1Uy^uVL;iU z{^%0;h93^UTkbDR(ujv|(Z&#h*2%h8m0cKJb}@?_OMm$u3Qwo;OlZt|8GrLAr6-;29R z{MSeznvBNaU1lFVY^Cb~@s*KWYnyV0T+O?rOZW9qk|5DLSV)VCnz}f3XqjdfeyG?%pPf3W`&PZdu4NoRnR?sxBElMB8Y zZcL~b*hG6=+ANW6!Og}F6b6%uS?VlS6(IRc5U*d(ZMTRjXDc~|BuN?j3x`V>(Z?>g zr!Am9!(b?gUoo=Bg#P*SZrtIWdR#F8q-t?3Ofw7GGn)vE2|KYXBq&XJJPV~w!ySo8 zMJgQ&w(wyq*XQ4uLJylQ2cXpAlJWq>9Cfj}DIW4yZ3C|(3>DU!iob=psU zl6C$r|G@7?O%wb6TzdWA8nV;ZD1{1Np^YviaRpSw5pW70nV7EbE^v{%w&K5JPO4i? zP)kx2Sdk$h&}yZLkhL81Jl5Ma_%frSUV4>RBhAh>;9x0yIx2|dsG!azXt-*BY>M@vac zhUf_h|D#tf;~PBZrbb&-Qux(oR^S}0E%8~tucF2eac`gMZ%gyfeAmzDpFi8!7mb(e z`EAr;S7h+Y2Ks2jv|&cd7>?h?*-)1nBSOjPv!XFxkinc`_{@lnAY_JhSQ#5B!RySB` zm{U2!D(Cvra08FI>mDd^Ae8WP$K+&_`W8L$*vQ5NwudF8WDQCkd zh?gI0hlUe()2u^x*?<4uYns6uj-qg`>_6xa-#L|>P->OOB?WE-Bd?^JeG-{s{~d9n z+H~B|TmD#$yq<(;lk8?nelBSK`T4&yqK!4IM@r?v&};lWs#asHY@kb|lnQ4Qz<)MO zgIe*8PE8#v?RR;%D{bs@TT*6myYcQ6aC>f)=ZNo@xUUn6Lm*-C^m5TFa5t)4;%-bxj1T^;2Gj-9ADb!Gkf>f8>#aj|!Z&~j}XbC9zW z{kuFUa3f`M$VL5Un2 zu@Xix`hr0aYb#2V5y+m(w)NY|ATdckmHJ3>0SNzjQ!k=D9 zpQzf@=Up{bFsB!-jpX$7e1>wkl%>}qCG64D7D&0VO$2W}f=aW9n zC_u!q59<^62SyY^C)kQSFpA|hvea1%%&Dv;4@mv+)hX}GbmoPkqodw4=#;SRuP-iZ z_$qPfs7hJouVXK6f-;2W2=xjJ?J40zO8(MEw|aiVl~g@Bipuw`Q>tj`768B`}_x1~OQWH2;K7cJEf! z4=3$!gl&`m4QG&h5je>Yjj_j7Mh2K`-A$w?G4ZerqYC1qJOS+1^vb|{!7 z&vs{9Q$vpLRbGENNxW#>An5HR!-g#-q#dTe%Tx1z$AprD<~lY&1Gr2{P{4sE@`L;DEjg2LQm9*%_G)Dr`wlts9^Y^jnWDeBS92?xX{5S| zYC19dAc8D1eTNk^N{7IW|L!^w@Op;LTTwvkDhM<4+2Z;1hFyD zV^~^hNdm{A+(T|M>%d+ClJOZ+>}x^9luQcm&NPohmQF9-_uof(&#W_XN1YaAAT#{odk z_|@Ft%xc#t<6i-$K>=HZ^INd)4+zdtYS!cq( z(wFee`(ZT3_nqa8i|$N_{=5C}(vw6X zxqdrJ2k+t&zJpF0b8vSqCTSRZ`1^6FYkGkwWRbX#gEKOgiLqgSqrgDvceyl_Mjxc1cv=6iYsti0N=n zZ^+k&Cu%3#Ec3KQOGoUDbsTZjwLv+iZNi#(e8u7u!n#B}nDxWj|LDA{j+iN~h&W-w zfwX!Y$_aKt>CVDLV`uVawwm9vbtGQa#|W7}>KQh{=^D#BE(gE(A)2i{J6Cp(f%U9( zp(OTWIs&7ge_`|lxlmX6o;@K0QhuNj=n3XATzuqU}65{|L z>=2z96xd3;4_9HFD@j{)3!f=y@$N3R$(u``mzHygE}$eNG^h&**i_9EbP?{e#D!Ip zd`7hbjUiqZ7TQ*(HBT2^z^#~;rgxJufW%nY2#NW|5i4o{dPUE zYzzeKs_9Z96QZ4=)+Pmqv**0 zg%#!bRd~qY)2H_480B|&50P4cyr^iM=HyHWG51`q^ElkI0(0hr|FUBP)O}Up{g4N$ znLTdgkR%(_xr^-S+F^}iBYe)7R9Sz&Ml-P!&Jb_E62%+3NX8(NP5v>71*3tNSW72< z-Rr~%TU55Lx5Wx7ejdg6?oj8puFt1_JQKz5clbTjud0f+K|}AFikza4PG?}!02BJF zkC;wJpHkMw^B?((d&1r*C20p!-H2S^bDK!HTqpfdYmq#XFk-fPL^uk@r_(M~$PYc> zxc-O2s`r^l4nHij7%3VNI;mldsg!d<@p5}dz{I?)mO4Z-)K4e=)b_=R>l3|kG$`Fvp^e)B18;jd<+i%A;kmvEW>JokF4LT0BeDldrf%c>8`e^q=5^YH|TE}#3HZ-VVOH#oK6Ne_p3x^cu;S^OVOD>d}8u@8}+VR3O(vXmu&jwO%{{7@WB zYARaxZAN@*_anir$%Xf@fc*rq7g7sw_RR_uVHLF^;QyOPGq`^Maq1*$S%+|3eeWP? z*)KjLh9M?oV*=4B7}a-Jno0Q~em7%@ynYwT)>7hnDVfc9S#(V+Th_!Mc!{loLn zu&F5>N-;K0tDJi@5F*%0o+Ov^oE{@5 z*OnJP3i80f7CFI4rv{JteHale)B7$`XAytITRNfTn^t;rU2vw~?X8XL`gq#IVm|Qg zLGm*2uTmdR)Jt-8{?W*d_rkCNqyWDI~ekI@-KaYk72BOPDa;h=0Xl;bwii$Aa z+iuDIjqGq=9JjJ2dH(7HemZ0U?1;QZbX_47K>p;o#j>J0sQ2}EeuJ*)qH;B|2A@8Dky zY8BbOk>{K9U_$0OBIk9^miVr#Pp6{|j6dcu*e)9~w3yk7gC_H(`%Joip(;!R_l`dn zf*%297G#{m8>91{<3vI-a&ApEy*R}<-|!^Mt1?4ybf;-~FU@bCZZn67FjuxT|ATvR z9JCva9zZLG&9gd*5tsx_Oo?(!jblGuxqy^X=5?FT&A5^Ugg?ryPHZx!m`#K;f&4Cx zMt-$AC{#QbcW0_3FN&m?R~^j$RV@I#!Ld*PolO!8EF8zfD4K3&LB`@hkGY2VjeYE^ zXHXfCbKstyTu$t2X$dAW6lUhqD)i>y%$MT)+UDBH!A4LHx?hcioS~D}yi{vH6m}Jq z8m@de+3uVyPL1oTkuzh0*};)ULr%`jEFhqPdY-ID#%`{ct6>&pFE!&Hix9c{)NO`z zm%H4C;N+Wt&=V>6vYNmweC-;O7efDDon@U)Q(n|h1zBgqS9jp+wY&t8-M>oJuX{FQ zXg0=7it)0k>3iPr{2w6l762k*g@%Ywk(|b|4ra^JcqKG6x1A7K zN^n5+yI+FAjO18V0BKDzrsnUp0?umgEAp?GEb4V5P8Vfej%CXCE~E}n$`B1MlZ zx|q%QQXb?}N>J|Nnx{^%LFpNpIT-#sUf9adj!VO?zu6P^oZW*_-*z+KS6}R+^0tlq zq_nfMnMj*ybR&<6#v%Ysjre5(tonCr>*ZTPekW&}+@7NOr8wd`vaQG^j2I%x7oDp< zrJ;;#FEvce!&X>m>-tLMT2tYpX8oy>B-9O&EKqB{h zNuipBYGOcqmeK_mBaFY_^&uR~2p8Y-zxo=kF*<4!?!K<@mNzy*5~fzc;&dzkQdei$ zspV~Lw-nbV(!t%*~K7_m21i+C9Uy5g@HU3{bf~_OEc+SEc0^(9~gq zT-eaIA(YNX|8kt0-(w3gr_YX$Z=W0(v3EF5@~WajQsm{SoWpk&J-1o(!T8ZQW52K$ zRtg9R-f`>fJi{5~Qnotq-Y^C}*;%|b)_!9F+&A^#Uc%cjml_z9LY2ilC^jMd+?Ljc zB&)c_H3!Q_fQYMKCJ+q`UFt5q>S4aQNj$X%E+L;kmvYss+u6&jRqmLhJ^qT~ws$bj zfd3q^&+8SjS*|pmthd^gQ|xB->`Gss7!ztSBqO5o5`f}ZE{rLdqFHEndtnfU&>dlpsN1>nF8+dmOy`LDhm)|p{~RX zfDZ_dOK@9?j(*9V30yGSzTVH9Nu-D<)uqwWXkoZJ~y}Jxcp> zIUp5fs;lF$j(#o0Y@NM7er~CzM>vCB;qTv_q&rK4br>-bk}(@i);*^>cYHo1%4}!F z#l-kU-Q2_GlT;oO$LIO^25sEo5$0Mu5YGELCjYa)|IXCgx5^bX^Ut6kKXwBy_uxw(tVIGE z06VP6H_qf=eCq3WKQYm(@|c)=+<8w3w3;v7>}2rNOu!8c)ao1Ky?Gs5QFgBD$2FSD zZe-4Vl$a96_5&Bf&#=h>BFZXz&%7^J4WgjeUtE#-YrDwaEu|Aj<+UK@ylA;lF}-qF zCs{kw)o_^;N-;A>$(f23oBYJ1HzPiINOzt-hY1yj@B`c*o_MqP$l<;_e@gZS1@x5< z4|_N&XyxTWk9Wu|+xQc;o%FR|_F`Qz{uOREOji5o{E2*#o%m(=xwCfsi6%#BVSBpj9L{g~M zK0e-s8ErbXWAW{hUJMcOP6j=>21(a^K(PArhqjJ;ol;j*(r^HZiOD|$E7H7*1URj;Nx_|%Q(Q;K^b^)k5eRJUFTMXApS{H?P{l>tf`i7rf4t`- z6)Igx0oo1iwd)fv*!vTdi-9yTZDaz_l*a|dy%m{Yq~7SVPx)i9m#Bvkz#^Pw{x==M zFDC3-qb><%h&Fk)+Jhm0;yeex**i})9hojNiy%PgER!e$t;)e9!ok7bmz;nDhorK; zu(H;0OBlfAU2)>miPN3Z#WfLzApF(t~anBGqfLTz=Ic*+~Wl!eoZ-qn9SuK9~Z9(Yvzo^?Frm%2#ws0*=Y<>FkiIKcY zb6PU6saN)DNS;CZgc$CYy#GL-fsx783*eg{zDi2|_#khFLZwgH?8$oeZw=w^8ih~Q zJH9jTVd;|>fw|1uFN92w`9jIIf~N5zd-1{1Wdgn>G&r+#l^FLe4m>X?n?a3D4yyvp zvZX}|0=uNx0Yc{?H=Ba6>&eSRtq1~yun9-2@6gV-Yuq~tJP`!$SlFRIN;GrR>GR)xo{ zy8>R(a`7p$zxWD>DOo_4GcrH9;^BU{Xp|O0R2|YsE@(U?d8I zU$6c;%zys@ZI4@B9yV6V5y|;HuXXfJNlE=xiXI|YqFeml5qkJy>jW^geWvZP1BQ~M zq=rVC*o-&upJHNE{zJBo>bpG_)w2hgk0^)ao?z<#$R1C|*CnR0K#D^nt5NlurQ+j9 zAk-6M6UqKi8|NO&!b(@9=I6InExw*8R$UWQ`6^$W64?gX`y;U;4ZBtHpo~I3tAW&s z)DT+!_yLZpo@yrvaIAWQrDqnvAx+PIq#clrqK1d6#+mae7p&r$$F(k-7G{2m2jlJ-d z=Q`B+wF#rRGkr-Bz~`v9tZ9h$>aBu61Yp~xu$<_Hg(WIZvt*tVQ3D@KZ^nIR5G~o9 zLi|4IU1NF+GpA-jUB*lMGP)D)Z25C6{NbCC;oKa#+Wb}+b_JLYK}L+6JXJ91ARM4y z8XMCuf}%0khp`O)0RjCNtEdort-O|0=Kge67Gl;^c057f#2qaSvM2H!es(&xHJIbz z(*yewc=?LtV*n-2K(_TRNss%7JT2W!kbbDxq*Dp)Gw6(3{$=ZKsh{ckLHml4!Fu;o z#X};4Wlk>leM$`mHYnzRDFr$dQu)omc_%HcpECyjhWhds`s_SS5`IDhdIjo~%}~0D zsIEu<_e0>N`hOTft)xDYvc?D9gEsh>Fi29IODsar-QBR@aO(hv!z3v-+9*DHa!Nw3 z@0C=!P4L`li+#zhUGo1zq(jl1*SKZ^)2MA3}`TK`z!;!bZ0zR9iC zG$!}2?a^@qh3@uecb)14cExAsRIvdbmT7U!Y1cRs!DMVjtL3`mWhVAIo4AKgfU7Y_ zGURZ1VKTf_kOpfM?LrFO9eg^gWAIqo;r7~6UgeoB z1U_t5CvDl;2n_SL-u|>5f2WrT))Wshp%QV$8^Ahrh+O!GRk$|TrvguTwFd3Xda-E4SIiy zSlx!ocigaXI`Kcv3M!~JRK7+fyI;V!y~=g^*W0~Ky#N!6LmxXkiK$sEl_NH}i;(>K zZ;fvQg5WSaHh=W2)c;&ROf?-O(3tQyw#EUj7t%T?gZkx1ZRg}zMCKETrA)j^8;h_P z5I2&{DrRnOLpkeMSfn1WqzK|B75^=@?m~d!B6G*(uZYQk!`0DmWq?P2r;5($L>i9H zoe^{G?K_zSyyIGi;0ud1(Fbj;g?j4^w?so{+ zjx(#Rcj;y0w1xmEgw9}`I{uIumAO&DCf(--jEQ1ZzyBG z&0Fq$qS5U&c$}j#C38N}WO774-@+uzf34jouF?{Lj~ffjo5G}^b+&d8!2CMGGKaT` zXOzMRURkYP*3~hdR_&oO)%_{QcZ;<3Jcbmj>KfxEXV_Pj2Vq5%=G{bOJXxogxv~F{ zU&0%{@q;Q#Q_Q!>~-;!(j+c6Z1M}AE!84`w&mZDf@%qhSYX$^1^bZj z|FtfX`e}k=6{tu5u}<35`;^W8f{v@yu_U6|@uPK5I1gOCwIBp`%ZqTaV{HQtUveNyl+Hw~+t} zh^*)KRDd{I}`9)n+FppZ3^rJ!B*tjyx)1uHVBZdu^g}0UL-orchiVG_p#H`#(&sa&}HqUZDBY zm&DTUUNO9q2L77_mOi3>kfLmVBcKIvtOT-)U(F5D=>eI9@-Y zG;Yoit7cJGYJhgc3Mj*$Kerlenhl{H{&-eqQ~RA02QH7%W!&SJ(?3!s22!J5y? zHhkaPo>wlDg3VR;L8b5C4_KU$k;{6cfMCqIW=-e&F&7tH;6IY^(x{bBzMn{f5uuUK z{tt6Y`VCEQ9mo$hvM3;h8TtFa)8R=b$Blb$7Tj10Was{tka(d0S7Xw`weLY<)otlb)G3^=nAi&X%RdAg!1li!&>lG_7T0%)TyrYaT;7Rqv2l4>nrI4W>W4z3SI>_G1rg@bqKfTX4?i=u(S z?e&)IjZ@|$u-c5hQfXpWcV%}uX@!D)cBoraieA>6p1X5yvaSBUQ3yXjm|rG@zmaZ* z5YL87^GUF;7X}-tzPPu>t7oy(?!YwC))c z4&@{t27n2lmBz(Ueo$1|v0c>%W1loEg!H3~EHwYZ_UC|z@BnDUZu=bGXz7H{_w)=W zsxYy7 zBBJHMb92)y~FBVdve zc8>Y%##N+^b5sCDS3lm^wl<;+*_NH%T@v|3t}S*-tQZ0g{_u$SWrUq;S-Vhr&UX)U z&HOz0Gv6$h9yVf6K}(&1H8M8f9R>sM_!oZJb1DjK-ZY7bNpPwt3Gs7`{8xU8zlaf(8Rtmi>>XgXC zXqd@~YF2#;gVfl#_!_3tOfBGH?OMJ*Pkv#djp%p!Ud#B;@>-K?);RlM6epOp)!^K{ z{w=4LGyfoVk0lXYSkprP%KhsXS7j>t>`#?rH!(+MM$XmMmv#IWy(%~l1VF`V`o zTjxMx()D=!NZuEvra{zkH4wpch9|!$D6@F;I$fbsMo@y1ppH$POJIhX-q8*kCgwDV z4vppfdREY=UEj`}dv~=rbLm~i^JoX*&$8zDAyu(K$rk zrnGd!JWIWSZi(QF=R6rIiU|0xVp(FBzrdP?z=noX>zAooKu5)iPc@cL+8iwnzbcH7 z_B_sSP5EIuHPWKwFI>e39c?w?I`ZuI|3%OBLmm+DOr=dZ{>eWG`uYf)QMUlr=<%y2 z0I{&x?o`l=tqg*U)a&Mmj^iXCI5Oer603E!ky{aAM9PhS6oFkKqlPzJRHE5F6~3!0 zj3bx_I+=4)ed^;arRnNU#;rM|t>dLnolz^^CQk?FEy?e|N1SF{xEG z1W!o?(=ke_3jye5kz)(A_?TD6;<@HILPx%wWH|P-x%%Nu7P4ek&bq_i=GZ} z52TDFzX)@4g8~SF1k|zWsi(BmiHKnGVhR3bzP^=^Re`@x9|_c2n6rPKq@S2DH%{$@ zmdaP2pep;c7Dr68gGiFpSgeD?EPqoeS%*b&Hah7UX`MKB3mZ!7Ml-BU$j9i;+PKgU zp^urp5*HTaCFeImId>so2DZG|nJnV?OcAhmUBs>=#mI6|VeEB^ImJJ4QAiV8|JHnd zgun6w@l&-73Y|2X5_cNKg&HRHBr?rV#Ts^IjzY#WnNCyxeI z0n#R5@wQemUJ0Fl7!eKZLCSd)H^-9(z%omV%k?IEKw@wY&sZH`1eK1yI+5M8@8&q4 z7$DNfz%9N-7W$jn?odPYV|k*CM~EDtT8FH=)!{QkL1NL%gJ-$K^-))*)rJa{sPNs@ zZ+Ao%f0P>pYS#4It&32B1g%Z%iafpf0sFi5XqQnYF3<0Ebbh;$2JObo$c@f9R{@~w zh#@bMbzEuL0M>Yr%d6Y0wWB(-zH@bBJW6HF_k#Y-cBBGQ`OW|y5gYmh1m(Y%8WjcM zS)Vzm^jkiu#TXb~Mtudy2`8QDK&Q^zEd#@{gikTLerRvLJXd}bAaw84(XmiHfU;1H z_|u<2uSx0L8Qtv4L1Wx$dFQT?U5R$7De4y=4*j*Fv7oXKzp!peW`0{l+P63Ai!E|q)~KeZ z0}T3KOhpG^DmJdKP`5%9;{nGb0U@KohJe)g6S0JIQzN=-}S)lvXjPB6Gs#Z(#YE1y1DIp;i*3y*eQe%=eDIs?nrUZ#}>9| zvk<{vfuF!Ke4)B1phpRtJ{3sQUT>-f)&-zf=+zQ~0WQ<*a>a~rclzb#<==#b_|@{> zU>j&}y3uoFC#G5hHL+2S`jL`kd~NA;9Uqlt5WMVGS5d&B<8jW)x`8+B)4}y@t(_m7 zogKaE0y)j)pBYmn&_hl*+!iJ7?O2t-R>J$0@74$eCJslOG%~TD!VsZK zm31C0DB`MutbUl#uU-fYnYsIsKG$Db_YGx22T2!Hj8rfXVVQu0jK<__pP}$FuWbkM&*&C)P8c7xS6VqiVwoq4{Y3Mg>TWDVHm+JngV?aQ4^u z`Q0fnFzrZ(N=bI6UjiJtJ70RChKLfjL6-s-BTD{|n}SzS3#h9VgqCr;t(Q~bz0M5T zEclxtVX2@*66Qu$gV)hli0i897iCFYrHX>aW9>f77*++!7$3JHO4O>1)UnZU5^^WU$)BV*1Ow>}kE%)WFQ z=9sOw&XwoD|~{+{wrWCiAnG! z*$PD5yqo80-LvEU@=AN}XeBN#`VJ{|O;l%Ocme+Yucs#-8?`ePH&Gfq)LpU6v26l# zC$1tCK=7(ze4C`pXxcL@ome}Iu^vMq+TLFdX4_j|)E_9US@~j5=apMj(o+mjSohbq z#CrWhByN2xtqGX#0Nf1++W({Pl9njF;dq7xm+nw3Q<%|~jXjM=Om8af5_gn^5Xw=T`L;~SCS@JHBhs0OxD zHrUE_s=j;IHpKvv!s_Q<52I6Y&SeLK1l^fKN`{a=r#OElaG&g7dp8DVY}I0;i(RIp|Ll}-nbbPHlK zTOI(F4KY)?o_Wb*r)6SE zD&`T_@%&EK;*IWe!WH0q%^sZiW_5K?v_R8bTe*@4O4~|UO1${#1=4Bmxzeqlk-0WT zMVmLqeSt-$54|H8jp2ci%2M5tlnyB!lqpWmBr@qq!5F3Dqhx(nHhRsK&5tt$wiurl z&UmJezoVvOLiP2zPL58S10bQ#Hs?wXYw+EA#j7hKvK>({p@8ZKG8ty)@+3~)&-!>C zz5>FeI*6GZh)^ab+!VK9G2j~AcD8mud1t*lS)>R1j);lA=_$3p4um2fxPcmoTtF(T z0-(mDm&zV9%3(_|#1>d7kkz3bS6fNl-ErCI`Dm`Kz!0`c&o1h9Y z`A6(;rqYcGjifaKLd+Id8n(`B^R3<8zRh#fKL_(|IXT&*!Epj|BM*;s z`C8M_F&M>Ts#22{!hWP96e>sPvK}-U4StHIWV@tMY!J07j`?OaC(jtJJ-Y zptq2FaE)=5S;;z_4ru#mV-F9^i^K{|VVU-7^F2UOnj0kp%hcoB06Q(?X@wli^+QV! zA~{ZV2CUBH1SJ+m1v``_=SrTQ8Ye+HBWn30;!fWfK>|5*y>I)k3!+!{23k^vjT{w? zja+-vvYB6ox*qDiakyB$@RY0M0;v1Mflb;4-^_wBkkKvg*+-&ye0n3~^ zG#n48Mz1VqX`xpNDxRI= zV|h9AtG8{qyP0m7o<~ctucw_P&8way59cv~e11j$!ONu0;Q#ZyzlzPWXKN=NXPBGk zR-48X3$~O;#XmGx(2y8FzfwuG`kD7U7TYCJML`0DdzBRWdTP#>#XSg~(K@z!!YdMp! zUo7vR*VR0;9zgXO`qo!oH3N3Nrenq`WssuQq7*AbQwnKsRbAu!8j=fvxH@iic2>S(&saIaM|q4?tU z8fECu^!SmXRDY@i$h_0l%louCfiZS@%QDnw@@mA4MYrUiByn3LoTF zWb)kKrGJ0gA79AJ)9wIm5RSdWvdoDq`3sa0ur~Ws9Aqrn$#MO1%D<^Q20FoM(ghT7 zKj$l4nuCp;s-q``1P#B7pY-Ew?=luEQBkEY>vd)h(prtVWKaobk!=w&wWv@wzZ=0` z@dA$OM|ET9$B&nDss&%Zyo?dKWmFNld1n-O{|9i&T@hjAzQY^;ds&MrBXvaWmeRhW z0=;xyd~PV-K-~Xo0d8)z6sSm9`us(@0Ax3wCfS47NE=5^M~Azf#UXv-@i7>%<`j_N zi;j*$6%LT&=o0iB?(eEB+Ag6rpvZFpKorx}Ukg(*_(JnBUw@@k9ryYNJ3g&H@~f!)P)oSPj!LCd0ct1!8& z5%*=f>Hb5imTnr?bP0S#vTkV&I?VST2*8v3>_+~M-YO0GG)RzwxyBpq=X1oL>S zQY1{dN?Ju==4NBii>*&8Bv-H93=}N3#uZO35H!ZEUNM_kf)9^y9q)hz2g2X2hNmh6 zK}1A?T>ol*|LCs}M6AZ9qx<3!LmLPJ7Cumjl%@lMl>2lyL?66sC^GIxM)PTxF z0LuW{v7E;Q1VmbTIwSw_ADLT)yYWn0 zp&Q!x0~NmEfg#Nj^ZfpDK76z-39Pm7w4uU|thODw=UZTMcSCdA-3;#$Hz0w##t7j~ z6Vm?*^45gbyWx-D7ONDw7R_^13=9kboiHq!M8TfLW$TkLEOVNc=^#>%(wc$_mluHM zv4&QSo!R)&KN`;b{=R*DDOuaqxJg+;6R$f^4rn(`k2t&(4u64gG4#J4AhwGun<3-< zY0*f3me&u#$(2?yX+*)tH?@5a_gt!|_`}EFE&St3uslx}-hNqIQJP3i`%+u3o@xF? z1%hhF_wi-6{qRH)cWwDsGhVe!l?Xcbf3h7jX-Vi!=KG?_lU-WNF-4(Eu8Lm@H8^l zQ)qA&L-gzG;uOB`k+ohBq$GU|c?h^97b?{&q24%d-Vl8BL%;mPFcDXB${aXU&R*Q-Jeuy6SG+SJD-f5kXYm8G;gU0j$dR=^z01NIJf6Im?EkwmWxx?93)#^_-cT7Tb)( zqQPBmT3C=OEO~)>NB|ib{v@lJAlpcxG(O&MYO(pnRUiCAp)%20q!rxUGko;iNki;C zg~h&bwE4BQi!RNo1~IgSMSt>|7X#vll?1uWAa8u#sec9rzC^?4OMUJ^Wob#?(98gV zV`lm1`g=q&{ojyk=5tlcB6GobJ>9ULB1P?8p8I<-e}8Hy6lr?7A|P8j;#aMeGO4fc ztrA8GkVmDb)B0_o-KP)5NQ3$8*EH2OdoM%I^hIil_5F81K3b3pErsRh=UUJ*(6Eb; zBmDW(H+X<=DMWC`BcjOsQ%!DEvmo86-Hb!8cBYQ2|BxE&d@J0mMfgybS8k7_;3 z3%k}O@5SNbP+nf%i`Le@Q#@y1fp%8by?U1%?}NkrQx!!{?yhhOZq)3K_Y*Px0s^sI ze4ifTXe3V#Ly>&RRYZK?#DqltRlWc?%A>=;_BK^s#h8nbDm~aPr)@ujAW`_e43?K~ z`sI+F#u>MFkylgrtaGy}+anR1#f`J%({e+&`81~$>3bd_%@XR`5@dfoyt6Eq4|fTe z=#;Lf#^}cWjaEu6c|8&A7Vf{i#Tf^-;C6SuoF5-|f5PgEUjCUKRBO>_;TC5;PH5L> zZ+H8~T*_vdOwb%;mBb{h8GH{9N*nA8`F(N2r-Z|L zK%i9aA`3SI&I+cFrsjsDb2AscX|(FM+b^XA!|*{2HVcRUjJQee+SVWboetFm{Hcgt zqzJe+qjk%o59L4c-ini@_D4bQlfpW`zi+XhB5&t6gN!D#CU_b#Ea&&86Z;`|bN*co z>qE-ia01D_VJIlxy1i=zyl;X`;Jh!sTi3e%^IRU9`xSAxXmRxk>$*$V#G~WukL|KD z!d72yW3JYCA0;==faxEf7eT_5>aTkO9zT&gE_N&ulK`R&QLi|@#&*&agzK&(mKp2r zq}swQrT(Fu7?8)3wj8)qDp^KWUYQvKR$`IIl7(|0dh)35gxD~DF6bPIK%Z5(pD5?N zxIU`?s-~wGX*s3<2e;gm72VWS)bbecc$)6D4(Igjtd}Mxx91&yN*ozk3t6|xnlD-o zQsQNK)qUVny){8H>&4=_o%177lS6o4on=iKc@0==U4-|3Xzr4>n1)m}Osd>n_q{le zNl@t}N6sEAv$bu>Zzp8|MqdqrskkFg2*s&(g_?W>~&;nnfBODWt?Sok?vz*6n(HRcLaZKaWoWd+Y z;-v;#a%}9$k5junZc|mV(jTu{%z9u5d=^vWLb#Vo-pEL27okXZAkI)w`$uY1ll!%w zXfHCw9U=w>Gn+e{fS{_F_I%Ry+M_>`zW!iVj^_~{MmOD3)A8dM>#6f3hvi0lOiZ#{ z?0~;tEvb@zFf$iJS|Am=qS0PI`OWvQWupt>T5zUBzM^LE_~ZV5I35{c^uPCTXfP1D z;1jE0Z9B+$>=#o&eK5}rR5>{rRE4VyxV6=4f9y=O|LT2guyyU{y)by4+bKe#th^>` zcR&KiHmIrE5h|Zh9(K%Wz0C89-;Z$Yq-)JRv&8f%F4lrZyvG;aqs?oBow>ig{#_|QJ9A7-c_ixQ_P*ZeG9ShL!=wDBx*Bs4!Fxlu zOCopz+GKSzXkSCcAWWv()MP%r!#B;z_bG>-*0eA9h56XdM0|BD3i6ByuiIxdfC888 z?|WYk5X5vO`))mdAm~0Yc_hZ0E0!0v*3raq+CLu1868uvI#=ra`%`yjH7nY3%$URP z=y=&Wui_B_`9_@zkvid6?g`JFmIH|8voWL<`lvE z4+xK8U~ZI(o%1~E2HC>ib~eweFbB}31l=d2$@mKL;2(GMm!54p`TBwkp1;?APQOh_ zqlY$o%C#$8_KQ-=PwGv3Ami!WXfeW9OSOwSRR$kx0`Cv^PEKSbBqWBd69K3fLlHAL zC{y@#zAM3ua38cEzv5)cdtw4EX=tSt)1*SpsH3e9b!gf2f;yEm)^UnB9A8E^4PT5f z$YqL<`P(lN8F_k{7MG3 zundJzR0M@Z_iA%iainasCNQdxdl6kUW_M0C&ikNj@BKf=YkW4YKfFH7ASlEh|8}7! z%=zKYqGorC_7{UFQU7uCKWUV;#{i+xG2x{Kc?%Cm5AJvs0Tlno2VOq{W4@!R7F`o* zpo1%DZqhOKIq2>J%bB#R>z!gDOlzYEWBl~N%Xs@aij$XOW9sTrm0Q@Q1>s;r@ zfRJ|vL_>1pV}0vnUZ!V5qL@CXw}+eO->u1kwWx_OIg`0%z*S?-fQ8L-@B2R+ENh!J zUF6xSqSB9{7;&v{B4~~L*!{rEe?4YG?avfoXCLR@i?a7PB>KjEMmqiLV85_Ga9vnnohpa1YsCvigrorF8+f$l4`U#x82zlSAjc!h# z>$&S&5T$|s6~1l*dcZ3on?qQ(h}b$h$2D;$>&7dC`xm#~(hx2rpd^mYPP6~w6nT>L z4h;p>@clHyeTK$|12z`l8@bd4rLS+ied$8(7M5fFl-UQ>k-iK8*b2lX{m;LP8T?Xo zUVI?+MED&{lG6~5_=ew|;-s`1dp)Q`vu8DJSzg%Hm4!x8zB3Hx{(8h6r9qQ~FECFg ze(dpfA78g=YU*M(rwB0=i{|}GRUfNM7pf{+%AX#VPA%n+{#pjHPH%d3j7;seuo1&? zJ9s=fUuu>^E#;9Q|&wFw1|SwG0oBq2%kX_G3^* z5(EISV9(gJ)}TP0j<+DyP#QdFJX78zuekN!ZN&e1I56L_wvP8@rs3Y**%5YgI)=J+&qtLB-8_-YABFAx!> z-`u+h8!fC_yyf(L^Ng(Oo5W*kGznZ&6MAM+@CTil_@vCrqi2v%{q6ZWe3e z^V~eNK~y83RkRTfmZPt+6vupiNqjXNNC-4mhzmI+79e!^I(mH8ohvn5U!PflE;ls5 zcR80$o|XFopM!=(M&_Z&!B_Cl(GR|>sX#=R=B{9|3e&Ea?|(5;$uMYPi~0&?{HRv5 zYQqwB=Xs`lXLRufPapQpHCf!{5gb)WKfwzW)aQqXA)^DT-j{s*{^Pm1CBqSyH*_#n#2sS})_t$h3C`wKut*G_0c;)4$4mHQRu3-OCd-YJPgg`dn8x zuG`@ZAO6+EA3^Bc@2j{JL>HIBnkwTyit^g&IbM;3+<9CsZkUUUkW7Jv>#L-+@W6Z; zk23&heBX=mc0B-<=p&1_Kd#dA_E<`!tAXtdF;(~an;z+mjPtqXH_m?Uz?1OnGgSp% z2v4l2fT&$~C=^P*jdiafB7*4z=It*pz`8?1_78-mg79q|=&>f(TFYGjxu_WAKTa`+ zdAv>f(VGy#{8T9fc8Gwc#>&wTvEyw54)iwn3J#wIDbnYSjnafXiq7?4aKko(hNQUA z*&4ro&0=#kqxrL2aC!`6fbXXY4VOuKnAa})5;4f=LpkS%hZ$_I8XVhK$l`zwm8H5E zsee=|&Wvojw`XIU(*G0MX|(-krnet6`2D%8A+`(AwPLwaF9Za(?##CuB+3q*mgeiq z%b5=r8?pG^k6@pvYiJm5k7UfY`3XG(PJp9Mt{FXNo5wWZcjDsWYPi2#Pyr!w+nIhO zqXJiuqlWdU5Iv!P#QkiFz%cIPxj{>2CaqMk&$Tvo;SncVjI3%v;;<9byiQ-`Cp5N* z!n;#Wl{i;z`BvBJ$eEg&syy6G5Komjw|pcsgRR~F1yzi3XTWv&{+^2)c3Zacl%=vh zaZ?GaxQ)HkPPnG#%di)4yi6oe(a^E?>;4BeRwP_4)A8~2=va$iZoI+g0VbVW72|Xi zS-%z!7NO4`uWb4>e15;tCBC~{a00r5f|77?Ck9iRg?aU5BM5~+24J-=JAk~%R5Un@ zj`ineL(kj}Czk7L6EXQ2?4K9glX_L;2AsYR0|IXyI)4kfn-tE-HErSGFSzV4A#9x~ z))U4@dhGH7UyFNemlY9*oJXm<=8DG{)UvU0#<{Z&1fB^en9SfW&P(L+-xaaNV?$pf?e;C{aI;@KT<)>`va> z*4PXTTB79zB<`l+n+M5jaj*}ejzmt($)G-NUwf0YG)67zMcS#?BvOD5BVzi89A`WZ zQzUft0e%X`cZ%zOd%^*w&@sT9`J*|03FtCwf!3l}{tos{R! zShled^jR{eCFU=Hcts`RUa6T>?6UVgBYN|2z25Nmbdb{N{-2IyH?OJb_;%R($;ugZ z@$FsMv)UmtZC^nq5qC^-&hRhGG?W1}0|1Jouit*OR7D@dk^KQQmvOh)Rz(^>4t-X2 z?lmeZQ1n^RDPbh@D9eY@(!kKu{{lHG#du_ws$)aXv$m@0XN0|}Sy*bA7FyEge`S3y zQI(N-uBw)S2RM9cl|M%qhPuUN^AZyJe=tiD5wj_Jc};0}%&`+;&Kul*dgE^k_LkWd^Hzw`Kk~kfmo=D%-y4IkRgUF3*cZ5n zr5nI-+;K4-3KTP26fZt@(@;vqQ80mlvL_j*tkU%K`0R4OeX|RFGVhy^ULTGF}#bv(rc3I!p(iQ9m6Bi>* z6@4g&+P6b2pAYZfStoqKoo4$;13HzO{nPWZk%^rvKgx!MIO*tE$zxuK8q+CGPD_Nh zx87hN`7IvTA;1J-%cNoQyx2GU= zxyIVfKv1t2c33*&LO6W!Xr%1=1`*(wKDOPX0x3JDbMOnt0C8izAV-{Xto{tIqsBis z-sF!h*K6U=KH|Oe#vtOh!M{uiLdG+?yFA=EJe1JTz_Dure1Lbn|LiwaqvN^l!K9MW z2(M!n^?+ksrHf|%DWXm0Czc*jFPJ|VGqY;z$})>ok;U+P&)OdXGZX30n#JT1;1KYCSWNwNMuY5aVR?h)QH(b-ZO#8lRUx zv0Tonk+caEr4e8R0se_9YrIgZ=H9_=naIJK`gpi>;FJf$zRSCs$(`k580Zf)C(VI{ z(4gmFa6&*3Ch9LN_I3t&xH`KY6T2^N`YMqUj>{- z=jLQeFkN7QrXp_`MC#&U`hrpP$aZcxO2|woT#21q%p|7~Du~kariw}9n{Etu3=lp_ zF}DzPIILaer~SVp2!P}Sf{Wf-VB@_=%=s2!P6mbc4p;&@7ne{bOqC){pqyOpv3m*! z{A^Xgmwtlmyg-^yw3!D7uF%Lzio&vQS)O76tC%HaW!MLX{(2w&@mVg`x1riB$zHPX zscQuj4qLulFa4seAV>6t6SEIZ@lzP@m-2i$`l1>;;>!2W6W_aH4j<%Dna~$~uU<<0 z8SRP^;y5e9++4V~GBGK$Q%<|%gq5@82&7q~1)1J)%0^rc%jlBP`Okd(9{&*Q)L0=_ zgPDFndnKDaiN^f*T;q3bB%n?5?eX&P#aBO)WG-Y-lll*`6qLKpbFOTq`M3S;xv7=1 zI=^~B>Mgvf@f%BcG@8||t?MxQ9+bE4#X*1*CQ~9%S zrJ|IVD}W;HEC)`3@>dOK7&14v>SpMX-8M1Mzm;7?vhN(jfAuA7*em{1{$K<=VVM8A zQP^a42+AU$7gK=np_gDwGxP@r z`R9eU<#**1?|;dK)PUX800r((d^{?xWdekLVuH?qBqxZ&nwoNF2SEj{C{erifNW+G zz%dXQbxj^_hcMBCBQM=NV4whtMoI_+P+^|f+7Va=z+W>vIf-@t+3HtEPlL`AE5sGD zxjBEgOI4z#R$IG7@w+0`3%w6l$A@^FAxV3>x0LxeK!JU{*jwY`YUgPc5ske&rX8QF zoq+)y8>7biJAbWr)YbFu%W&llpMH^Me4udXLOnOIEvpfdil0y&utZWxu?2&>j3ZHk z>Z5VFFJl+#npVd^{M^Mye#vj3;v|N_2kHAqPBx;-8_v32uu4sT_Q|gAf#$jfx%~xKV^TYZ7 zwY_ugfq`ln1ECnKEa1dN%Wl3bq1Iej5c~2q?Bm-%VN>I|^yn6|z>cNo{pUIL1+WUy z4*s$@&>pyi2v|L8S4sN`O%HKQ&=QHz$za>8H8n|7^%p~rzS?EbR4J33NR9k=S@w>-L|5o*oaDpez{iRJC?P|oS^s%95EDidT8 z5X9!o)Kk9Xll7nJtI>W`1x*3){)w+;w7;7ogUfoXo6)Z7f?pVOPmfDkwfSV5RAkO0 z3i8I~aY6TY;ezfx;Ku~YzR;_MKKf9?@Md%ta1 z4XP~xseiCUP-GpT2xz$?!7=B3^nSDkJ2F{KdZWtIekGmdmCE)wU z$8fdsmCvz2s@xzmU~cj!@v#@I1)!{RZf;J!EP?hvPvDO^B&+x08TN6(t$C}zym6vj z{j@V1p_QPghvUKn#CW7~Qh&=+y|>pRi}~VU3E6v_pYxJSTm{2c=%)J*G>?rJ;mtWZ zu>NfI+`5JKCL^uO{-@1P_|6UxvXnkJzrb8lCe`33E}y0?BaZR()M8(qRS5yQSg8E3 z7GNmnuwF)va^Hs%rg6^-$t2VD%X-o#Z)m8C(!ug^{SQ!JoPGFPkBvnlpY(A&t1NO2 zUlx%^!asc)vjn`lj@PQ|YtoaZ{US#@Dt=^Uhq|7&^PFch=D7dt*3)a)J_xk@;2r@F zJc&+bF(Pk?5FN3*@2tv0BdWVWaHom33Cq`*o}rZ6BNRS6X3t*s9Nl_)f1oMge6R9R zuGGp{6Ym&^=c0r4HtKBHt^n}5;Y4yJH~OPSNrW};>1n?s(2o_$S=zvoeE2vJrm3FX z=F4F-E8JLl{o&CXi#8Sg2}C@t1yqHaW6AIc)vp0O6@&6)5c2NbSWZK-(}JaCZ!~c@ zT_SQxQT9nygoF%$DcwPN3;*ONPgN=RLPYU_LL9z7bZ}}WUb-tMZgt7sQjqTS?jw*( zpDCaoxL_Lh@-oM8yy;_R%(LYkC@t5OK>eYX15eIiga@V3ovVv{DO!+`-#QvWz$q20 zBkFx+xAer(yfu>`N{`KE3pRysG+wg!)A`AGV`Hqn`FotKIxQ8x;N{+QdpJufx?(|r z+5rn=pJiK;*E8YEnRuF93K?y%X2Y(6#S;^?BrF5F z9|v~;?=mO=>KuW%AwHbXG3s*Z*(qU29=g7_XQ67(TIsv;?0$&G2qgj*2}$}5uEn(> z4wF=v13*1OWDwili$mn%-}4N)?tesPQO6OHmZ%m?q%tYu7JoZrs+owf$!$_bH*>w@ z!XUtomaQwprTb*@Q+Mu*97+}ueO|i}KWfgaQ}(&fxPAI1(4%u&6{4XiGiGMWxDN64 z6JS6;2Y8$n>Sd+uxkn2~ZmMMZ{r-vu;MFU23)1+PxBI`MbESYj$1=XHxfoa;bq909 zl{*gr7cutvlmkd)=k|%9mg|R=DRU|ql`?8uY1{k&=%#j$zJ!+p$CLG0#bx;}H>ip^(Km67bt2SdaCE&{2r+NHJKz`eX$vzw{%Zf!9-&!iqKV zipU$EKTCge-2FB(?1+qH(P}}3)(ej3eND__OK9V8vdF8JQdJbeOnP9iYv#KD4)FJT z8^2y6!8BSp#=PKc8b7e{3)P6<)DZd`Q2yOOMV`=!O^ zdQ3Vl(-7+Sg-ZcIf9Rv1U6M< z5EZyolfRzr+`d$*;FMN!zL61%*eq_-Roh-T7Ph74jBqJ6=-mv(v zFpmTr0PjkQVxK$=*73j~3QzyMNC274u^;0C%_Ru z@7Kc?kce4wf1lTY0D_kX+B>(242%SzDWA2hx{}aAr4dzY9Nf6iHdtqS{=(;?WF(_& zog5ETB*r<3whJFQM#g?iAdG+=FtJgcctf2XtEt|4}axzJ03+yq!`5hPGemFi-(F zX|;F`)0)$>j3+pAnD5gMm$gsivlgh_kOjg3FsTea&nc$KgLgQbu zl376FT}L<_6QK8=^I*w+_c4HjUokdOLgs5Z^Y#ciC_8t=z^P0CD0S9Xkw(H1zy#M7 zZiPb_`z(aUU(dPv(9zJ5Z8M*^2$LyJJZDjll_JFsSR1b!05*g7Ae0z}V+CpZg?3GG zP>S8-jtb^QgNVb2+g(nL#bzD9oManXWD*w_;P8HvC{Cx1#JgT z4~;@jn@m-p8QIB6ji@NXMt8evm&j53^IL;qZZSZ=PAr=mCHI^UeS#%iQ5W8|p{^V201xBKeM+S1Y0kB_=bD?1EnD06Ep& zkF2MB*bP>~YfTaVpEnmcTF+QosQP~CM{1PpWDDHcY>zy@27v?24@UU3J9`v~Ep#}g zy@80FSFc%;oDIlpfY;3Zy7HoSdUqE|O#?$dM#o4aor+9&W=`gv4lfd?w&}SAp^z2Q z#@_xs0=XGU2R|=0@gdFQhx`ymoh2bzH zLZ=z4thhfM1p+PIKItea9AS@X?zqI%7EuARmAmG9db788M}%F z8HzL+yzwry8N2d|aWd{r+w!9(X+tiwmP&E)KPP0Anif9uMrqBxhbQn4WEJhl?MRmB z#6P?%PZes_(<<6yx@vWQH|?d-HVREQpE>=lHeKR=e7|&j@4KCCbalBPJ}MN=-I4A5 ziM`Xet0Z}PPRHAfPo1c-@j6R~%v|1!zjd@k>%v z81iyo+$-n$=Hg_d>ur4X=)KnE`w(N%hvxSqfeL9nG4ks{i^KCSE@Ewv;%)dI=%7zs zTvrF3QU~=6zPi9SHu0h48VxGu*mBy~X8?C(_z0EJ#mzQ`l5JSAu$|dU)MOD#`zd0b zDp3`(t5Bu)2SCo;nT8E@__)&nzixltG}lVJT##^2*L5ATWj3XF0PB>E-fhza*-*?7 z6&RokBY(-$#nY9lXUEK!+(f*=&aoX*`VxK{f8ZuAA|mAFNDQ?cnbFr26{i^Btx9-6 zMuI$L0A(;SXm0jnlpcV{nb11Bi-!-IKu(tX{6Czy!`}}M>l&e~1H;3$nja&gj4Z8V zfS& zvQ$wiO&d{rB`5%*Vxqbmgcss=tjSNyGdpkJU}Ay5(ckn0&2jE7##m(qEx9^rsg6a- z2ue;J`L)V)F@$+5b6^?${L*GPJzWn2$?(e($P?%lkfb)6b}|sWh4b-Y)O8hcWZO!R zlstI1{|h3`!?SF2NQQ?dw*2RIAH6EYf*Ycy9a0_&k`%G9t`{OGWM03nN}PapBW>8= z4uFsjtjmLrP87pMhUAPOB9gumm~2PP_?F4Z>qS>+f9P_7B_7y2tq?>SKxQC%se;8_rU}Idy1-VG500ro?XB?0kofizu$II+GW93JX#?C z4-K4wpU)9*k6bs5R+NtEr`{@KWj1}kmV0X+`(OKH^_KBdVgBHf?IYinn!bsJ##R|l zM95w-bAu?C;oC#L4};cK8^q(I?gN`k7053K|VkAU!;e435zYg4l!#DzK?WYCo(%Zsm^c!eU0 z4Px>RL5!onTmqa^C@ps9b~!L%0q3z9hPswGVd3flWaIYEF+)eyAWA1=Fe&t?_3dH$ z;!3TsqIYZ4citpM0EnRknVwaQURR>ETUEk#?>`3d{>*9Mm3V5;mfr?VPA1L94qRGWsk2#*NE;h_ym0Zzq^W6XMphL?J(j}R2BC8oi*_9?IGA67|2d@nh2NFP`Q z^VRY0E-|KO!1z(z`J67D>8OG70cvOlx~2T?XhQ8#XbVB?#Kf{@lgfx56p!4Om3n&(cw>B_iCKif_XNl*!)fGirZK`x(aR3aeByVNHLmb~38Uh{ zf=`MlqY*F?vD@i{<3OOcR@1$k#Zq415Ex_byAJL7J&e*JJf0VL9#&+is&@mQ1?Xe` zFPX-;?`J%I1}vZp2l}Tb0>!!zg}ylPpyp()4Z(ci zqF(8W5_a8|G!TmjY#{L9F0R_WwD=D0lcrRN?FdBx> zk@NLc$16{Fv{!GQImf=cmp%4<4L`-tN96PzC5)@bSV zD-v-Y=ER}KrI?gZyR_s395cHnSSN7{Nk-z0&%x769TSOPa2pVyk?m9DG5h;sFZS9+ zfWpTVHPD!}$4AIS(6psk>1>KSmS*wtZKHP~{A zi*N+uE-(1TRYQ50WQ7JM?T>_g>CO|)=N>CaE}AtJUFM-$})@ELTLtKdRrCCOQ!Q^nd}^x&lXi|C3q~DJ}WOA zf&eeHSs+*<+yS!m&ueel7TB7xGyRq)Y&T43v+NBNB$I*xMsh z%n%ZKfWC!?PSPsu9QOD-Imu_zd~e{^z@yXI@J*8_#iWm_a&`_Cyj95|ebiRbF&C49 z4-|SOkY}IiX0sfnTN3t~tcxoC$j-%09eh$p#+rUt{8N)4Pg+3W2+qk-ArKGEi49~i zgHzpXDkcb-?MNLv4)FX~gEc08XlQuQK7DX$&R0v~nSb+m`W#?Db+B#DV}BoB8$P4d%HSVV%0m6no-{q5-}9y3z-DN zBv6vEi8t~KPTq3L{TUjO>@4^OZfBnczmiOT&^U29=SI`;PnYP+X(Meb+EIQ+9-~HL z?Du#5ItC=^;w)QqRQLwH+-to%Kb(v@T*x+X+b{274He}j`Rx+FxE~%q-rJ~;P5YaL zJcfu!EM-xld+)qPq&?IQ&*g=`o-%mUQ(@V4Jd`hdmWb?PelH&|qQLOjiTm+!V5Lf1 zHe>hu+)nO9Jnl$6=&tsFUHhfCiv-6%@BTVry)S^YLN*X4f0v#1(}I#pERU!#IYXnj z&az-oR%xB)vS7T39kZrCc=Zs0urejEuvp`GX=sU?JvL?4L#bbrWn|DL!)L#b3j=Up z9$k_j{WRnTX=?7E6rn|;20@3Sc#JqzvasKza&&6???N>6-HgNW*1M*NONd?O7eayX z=22fQz$iB%r#*1hP>u}^90yXeAXXr?qo*^}0&B6wD>RDuOn5sjGg{*onD&Hb7Oaau zRno##((n@cP;h*^8H)&~cp%R5I#Xdj*Lgl*H0`I<#ng;p3>GkRW&_fFanzP|D5@tWKOgj(;o<-z$h{M6jY+s;uuXChOOkv z*U!aeD9VX*x?X3?!Hhxzg)xUCA2=Z>D|0Av;C!y76FQfqEWNi0UNMDSYx?-m>1MKx zYkaE5DhzIZn*PY=o(Aw7$5+J3@LcVaQ$@#r9=OG(h2K1T3*QJP7PlR*7NI=6-)g47 zpPS$K!0b}XRUUjW5g&a}4bt|9#Qwn9Fwy%ZN}}X)V>`EkjHqgl$A7V0A3Z*USL8h7 z82$ddKwRiA`8Wu(;1Av$Jozz+Q|-Bf-b9whoziA@VRb(J4R^RyKRg3d2LyV~itspt zTg=mS>g83YSn$}=TvgYNpjxapJah>LDhIMkP#DvV{L=+Q5z55?7{g&A>a`ZDq*@Ju z_lZOZY3T%_0-V#DSp@)rKrY)w6lc2$u^A(pD9^T5*`$~cqXolsW5?H?Y24mAID20k zUfro0cEC)XMc{%7HmRkJ_@U-Ex*{<$_q_y{=HkKCv_@gY|CM7@;4=$1Q%88DwzTd7 zZNe&zUtlL+HTfKj^V_6rb1+2x{(hPEwo7QL{+&KH?swrRM*tc42kC5B%Ikr7#8|XO z#sjsq`#ClpQb{Xl>1+F#5hfEjlrG^$QLh@8a!oxxYFRM1_xLP8#YeRNj z0xjft&A2+dVGmqEgQppCm=g>G#a*Y0P5@2XFpFRg#=a=S*G+7jo6>0>TLh@vxInSI zQ{Bf5Qw0c0P`8xjki%wg8N?_iSQ1Fp9{%{jAkxO)t$z0|RP-C4bs}-U6TIsyDZhm4 zv)TISojLQ1ovBwORG>cHH~BUo`xiD(m3^i>G6K;StUUGvh2pi@YIvbxp5N`uPJ>Lp z@$=zRzO$DaW7Ss$g1hnRM@W^Gk{t3&H9I?RK3wM3vnVHUY^&%Kj}yBOMG{2zoIeQJ zlT1yfLO|t4S+$!#lix3{fzh7=87;l9D0JX$ZGH4D<(pikxSCSCW+m|+yKhyWYs~;8 z2Udh&$1+`d@5sU;5jHi6MIt#EU^6$s<)jjhd;@(L*j-^wg@<68g(Lo&8W zGG=nJ(oCA#e-WHn))f*YX{ntT+u+Q}0sUST(UsFp*^*@)vLwB3bC$(7>F;?~%?P$v zCPWkuCI=Mcl5K8rS>T-R?>)mD3uMF0j5GZm=i9oK7i}(Xf+26Un9eek#QT6x%kLgpdh1;(UH~?t_ zw~r(J((U0c`R0WX4T;UY9Xb^sf$`(}uNV9B#2cd7(&>$ixS(e}oL2O}gdL~s-U}J+ zto^l96c%<}9*#XXhtB$UQmD~=9P03_F7+o}9Voj9lb?DWRIzeN%8X6BG__ZusRfg4 zk1J%Fsrjh^dJ)3R5bmj=8_eui?#A7O3U7%P*8|bYn)p=t;za9(kKl#c!|F&M#%_W( zxYk4s@u0nM|IVhX)~+2<#GReud}xlUh3oN!fT>3V6ZJG9mUCFg__gmGo1grj&racBH{Zo@!#A2x znBlbu*H0%~$Ss6&ut-8@Rvp{G8sVd1o+?u1?@A(*9n}=E`EwG z-NH(by6LeOJN>;p8PG*f^S&*7Ge;xCcsBXX^oe6>z$?*iD?8?1(xzXJ^|gkw!pa&! z3pp+e%DQ34+eHP7KmLN8zwvEBsq>R)tR?r%A3h$TMbqS6{aybKplPF>k}z2LgXlaTfaB=?)%RXNgB2D2uHCOBv-r3v*Z3A5jd~OyiemC@aJVgXDT`Z z#X_&eC1!B6PuxjQL5j=B)d3wYo=!tjmbX9gi>S_8P^DyjoNOuQMeQ1EM@{{DQ^Z&0 z(jpPx-s^^HA0+?ujvxWSs7{7($GCtZwDJagtN75+y!0f@rKKpX$k7o@py{nRS#HFd z$-7LR4nrDx(+Ap26q=@RPIW)+jHI?lL?Vs9SAM3{+>GIhx+oDo8hj_2UXawqKyZ23 zrI(VnFx(Mv&7VVi6wyD@JE|;8Mr%WDJ7rHy>i9{i|67c-u`R7{X08-^k-_&x!y?-vqw`bEg9@ypR zQQV2Zi14)i=JS}DQ=&P2+Ox9xW~?bjp7VH3x=N>Opm;tWZ6qjCtDl@ge)}g_rQ-Hi z{nYO?AO(mT|Bs$Igip{Rz1d3???dBB$J`s3q0wyxO7PTFWip2*#*t{7WfGRBX%HO? zi^sN!zeDuh3OtxGPoNYOz{h(r#>g?-X*NVh8#DI+Dgt(=?SO0dUc2z(#AJeFOj_z` zK0+RUILB*bEY;QrVXUDPju5TLa?P2kEcBaRqLItF^aK4{PM02BD#kM zMyujp{N)|m{(73Yi?sl}C`!)zT3ktRcw~*o2()2dmm>vH(Hw@7#Z)V|J9ZaCzV}u! zQ1ppoA~i6i>Aj)>NvS|MW zF2oeb8L|B?t_fTO&r;LI6&KxzU=`Z#%Weh5@A5&^K`G-ZniET_w9AbC?-3W&%59b1) zG>7%Uz>@;fIZ(1ji^z=<`^_eNAG`}6e|rv|OZAmUo%ZARDJrd-Z%DyI+bS)wZub<8 zHKio88Y{!Ka6s4t2#RQt&^AfVniMH-BJ}Hn7tAvEE9(7wa}9!(T(0bBW+G#pVkl*o zlBYp~A9OFs=BolMjt%5ROB_zAa7Q#W8ih!~`sLujzkbaNh_zT5yoTWVn8#+MLASyP z+4%mQOuQ1J%cPsvBQhdS#&YBsH4}UEJ5p$^s&8tUUqIn}{~axhfkvedKd4pxIQYW} z&lPx}UXNSDA+oNj7JRNqF#Ix$NE;#YR!)3PJ!{^B3)@$MIhQMbH;*9NL)N zt_U|U5CMjAUnW5F>$_<(fqG~UtC15X+?qOee^6H;iMy+z@(*jR@1p|=x1Kp~?Lv7! z$tZ+Cfe_*0{f!fNtwybbRlS=CEYnul;R++FJ)?BW6ETbbFOFw*tbJ_|Nb%^D6cy>>uvA3U{37W}`GjdN$T%ObKG(Mk& zfS|*@RE|svmZ$mg59#?K%QW5V0RM%7#F5;&p-KQYDQp)}(;#zSgH2yWMk13gE|V}W zT)Ul~_|&AX`Q`4+5vyu`@7UC*&87|)8q>H&CY=niOd@klA-UuwDx5~oj1fU3+%};gQjLIQg8s+7hE-~RW z99TXPv|ok$j@tg><%k7`0MiTdKncx8Xo4zTgQ&6vQ_Zq6^q=2Sh3)P=v4_)AE4?%OK@lY;CSK9< z(qGS%n&eCuNEWkelrv7AVN~sP!=C>2@D6sv%J^*NSd39ZgXYxJ^9#$@=xZNi5Z~_8 zz^EM=zOg49OeA)8JA`ttb5aSFV4WaUse0nWzb2=z4Av=(YO_0jM_X8@;*)f0YHsIIBh25DHG6&1%5CJv5bIo@_vKagq)n*7uS(jk#>meje^n%T z`Iu7M5p{K8vKZ73I8A@jhUBV|^=VV~>NJ6on6e^0W6e(I)<%{l8DoJOn7jVfudTg) z^f(Lo>WOsUw)CTlPVI9%?L~J9=IY?lF^@|29GR62(u=buzC|e$-_e{%Fbf3HT7iYb zR3OR^UMcZQjsP3+@&M9Ce!emln?*t?>}mPaMoM~5H#H=5Uo?LQ`WHwICbVWY%V;=P z))mxOZ}59jRvmU~UNS*e)cgKsWHe}j&Eeu47F>r9D8U%gE`9*c)>gVPs!Xj3vtI&4 z;GTbDF?{||J!;gKd4Hg%)!6o6oip=}_I7SGFV{OhD&(Un{Qsw1W?R2L*}w~TF~+S* zr2_}hRc?PiO=-yd_nv#`P3Vw3_DEVPYjv|r5f2A8A+IMka-V$*PEULgGWo~Tun|RX z2p{ec$B0fV1o>UYR5!C;J5#%&{Q>CEWhhJU1o)Kfo`RzoBDtzj9~VZcNm)~GoF?oK z;RpM;3xFjPev%xPT?ZXtt8+!YGWod%4B3M(xPRM{W4Tq7FD{BgOKi3`dqx=7rbDiI z=mX@dLGP52x5n(w?R+`CyOiWjh_v@kn7dqiJzGMg?{X&43*;9`-eZOxN4<#Sa=H8aSM` z^SuKE1mahVV&~WE4vBXIS|J9$1m#Wuww1pAiL);*B@_-`q_Bv!HRxXyq+~?IdpLzA zuyIgy%lW6%bsMxE*a?9ftOzc4gAgrI(+@02eS_^=ak6^nf(LIRg{hg`EXEoVV1_*= z>%%hn**A=Ig^Wkx*sO_|ws*uIr z-QLB=0vq~CNcQbO;_m~$af&o9k|Kr}YdcBv(qgNlbqNXOunK*-bFVf$M zeXs=5?}G{zRiEHm;@cyuN(mx0v7ec9knto>We?HUspBOn=0%uqHyuOpW^sZT)g8D$ z*Bv+2{8$^83I*vPpWq1$yii9zzY^FuZ71yiN#3;jayUcu^LT%i@yOF`oUWqCktQZh z=$%aCkxqAUkwDW66j-po?Nrlb4OM{Puy%zZD_#`%#{G(DKXCRBx9-<^f8<^)U-q&5?q<7k)XmEA5U1S&2T0Y=u1t#aG*+(&QmzSRZ7Kx(#5*MAEhh3$` zkS@fcHN)W=Lm9`?3k7*AjN&;TE4cK(eY*wF?(IE^ZY!;%YWd&lxh=#TBR4lEqtHk_ z^6!z_Ow5X{^x{nvM?8-4$c>HSb8`=P{h@ae0R&$@zg+xOW<=nAAe^M^HMF-i>V3mLEGShvP;F02Gpj!2vA4gf>)1zpdW@mi!3XPdBsp)KGDbL1#V{2dON6{@fDJiK=19nbGziy0S??lyGruJMzbhHB5Bweagn z(_`v7G^c!}-m!)7GtR24dX zs{d6$>`+9JA|ihX#?f-|ItT@xLZX5{&&?e}_rk17O$@qgRfKOWWSbvD-*Xhyrz8mm z1KO1d>JJ>rh#MiCJ*BC!vHpcuEZ)zfY(%=0fBs}Wbtp>spP3;fpGN&Uvbj89XyTi; zBN6|6i|6#)D_#+gMt=Cl6GvE=Ug5L*@n3GaQ z>uq!n8_33N5rfCZ7AOU@s&PIswc$DU`1Fb_S7twl;Vo%QACjM1&-9&Ny-BGuMaFFm z>`IO`Xc+q=p573>3;KbL)V+jq@Y&Yqmqv%E$b|=uhuju#)QvR347SpCiSOph#3ZYt zU{ECL?jf|t+CM!ZVDXz=YIQy8&OzWOeiftUt*yqB;;MuM^cH|&AwTwExs9kwe}jmV z$SmO?gV=qmXm+{mAq6#Xy>q(}Eczy__=ev2goRz5>8mD)M#bqTfN+q*G%6!7J1M;( z=Sc>MZ#xfnj>OmgwhNV6A$^e%%NDj0sQSUe0817Srtn3rAOS4GH<G+>8B7)Z!@{vCl0=yp282~w1$)up8D-B(3f;kdie+Blgdco-$( zf{(&j;$A-*g_&vLv1-AY!uB(_u-^o&;~bH6)!{QWBr30ap~{`*SFQyPwf)?u(aQXti$pr;XqACaSTOlSFalEjrAyArF;q=}ZylRdn7HcalA6ZyOH(a|MBFLH7 z-JfC74LqZ#_m>7esBOXJiBFdbc-iRKv5J(ML8%j;=X7}cfA*GOid?5BJq-tdaE_oD zS1Bn$+`x$8ca2X67o*YA-5vSX$S{|02`*S+PXZN{6Tiobi~W(WK|9;4!CVk^tenf~ z#q`Cq_sQCXL?=JKWAY6ut6}||N-(rSD$hZJfsXfjVpdt*1X75Jg+xW_c5`x?v}H{z zVdG?%IZc{^)_f;@uEpJf&3V!2SJ&3Zgo4Vk$8a=)cmMT>D5FSen@)O7GJ||eVVy)A zVyvw?rB$?=L*R_K@Kj*-T?hyoj;yS}5 z(lUD7`_PzQD$zk@Y=f9I!k?)UKOL7D>% z^6|TvOZVUQ+lxX!$03Gwo+#oj?WHo)lio;l+VFlGesJ$l=({DTb{;0`7A7IJ9VB=H;K-K~KjO~BEPImTBiMohkC-QV=FpVWzSnFil zZm@GxfiV7ar*9)`>T-G;9SlF=efI^kh~;}bm{*08J_4NH9v-oMfgH&|&n2q#69($1 ztdf01=DrG32Y#7OF0&{%acU!tX0}A)jpi_IP}AD;`jO-)@cZjomo(SD!br%guKr>K z0V8o{e_YTT=x~!gp#W_bw?4GH8D{;khi;BhUS1&%28J=mYK(pz{FY=RYduPgs(~C0 zs0k$q^QIlucQ;&9p)tDvz@amz?To!XKu=HH8bSbn>6@p)R&rp8)HId)*-DY43sX~ZmKO1ZG&$(iZ#jwk`<<(It)(*}ijYC$C%vGBtlOa~e_)ZY zVtl}2`?Dj*9Mmcoo}mHJTq??#w+&-sZj*rCXawhrr;AGj#;v_1qeAu%sW0GToR16O zQc_ZOu)$pFgeWr7b3yHRpv>lmyGIo0mHegt{_ZP12b1{1k4$VSK*c2lG_SC|%# zx(0~H1tI}sy?-(O$=aaw!KqeviFsT3?DAbzZi6_qpXu#qn2JfA`274pM7+0eRR&v6 zdSQ__>TD^SHow4^7RVTbnWF41O@Fgug#@zmtxS47W?0ONIVv z*RYod{M`yzr<9b>QSjw-^c_yKE>BKdV{7V|g&KNHWcu*P%JELUC>ivg9w16|bzk?* zO|JN`fuQ+gkPi=7SKy(x7>D3dyXopOGWFix{!zub&wL9I+ptiq>`L_IX#H*m{%SL$2I<4+S6F+#+FS z9=vs&BoOz0m{Vay^k{ttv%el1;>r<-uPryU7e$P&CU}{Aa(3J-cD`5g03Nx`LN5%o z_Z?70m5q_dPobrl&zcYYCw(AOu6_hX4E;RX{DE@@-o6YZfLF!E51i0|mYAy=&g_`nJeX41Zi%I0YYV8@f?I16*mlMjUSM*1deSKZlI9;eWxDr*kQ)xgf1srr(!~r8 ziPsKggG9%4Bd~-oiO|sNB*R4U-?FniwC<8r&HqNbLwWrgQpK)EZ8j}Q)@P^jlXeUU z5XcIo#RBwzyJD0?9zrTm>`mufXX76L@^(zS_ddaG#d1r|B7vBd(4)3YizU9Uf*T%s zCCQh*G;V0%Cij1+dhd8F|F?hqortXLEtf4TvPnipcJ?MCGkZlL`!XZhD`c;%>||fE zWn|B?Nko~y!{@%=pYQMfqd$8*>b%bL^*WB{)UsH3u_pXY_P{;yp z={B4rMIi)?`kPTY<%bW;b3mo{wk}t&2`E(T1A?zvM-T_P#!ICkII`K;CapC1cSZE@cgY6a; z>%~PfMRV@NKPqawOC9H;P6LNtu8Kyp!r*&Z5I7a4>o9MBR_X3b28M`px1`MD z=wiHNgB2v7oi;+VuL{*N-X`U~E;m>CIvye&9vo!!@Orn_G=?iPb2$tqLFrnZ#bY?A z1WDjyaPVufR*}ey_1B9v#~pOt5)i>W@?w7FLC^?Ju#&E(rt46U89ET-*=gln2Lb{% z=ua7N{-gIhJgbSPkHrD6&DZy?4D~&P`eINnY1YSE!U77t6{3HyEg3!$g~MNcgY4c? z^g0Mu9UB%1pUy#}%m@nlfb;iDWi6yy)ctp>0JGCD_=pZ`Sxl-!STo>wS2|sN=!s|G>`)nu0Gnmo%HrGGZwGLy^+y%g3k`rKUR}Aq2hW zi zzf@d~)V?|puV8(%^I~=fhhY-~E+&%}s-*d;YSkg0t~;ET0sp@-<4P$^Gp?bJ(A5#t zMX+|_gu~-p{n0MCI&=}Wo^^4vYjf8zryz^vIYq?S2laB+YZ9||NKl1vMmZycAn~lcO9b1 z?*2$l=d*st`7t-YI|byh3-ZSK5{!yQ2mP@ zBWWc&y6e4tH&tP`8#9}Bg$>kH&0;!kd|Hde(dL|adGolTeSMYMm92z$weS^z^y0-r z3E5L_XWB}3Dm%bdXN?Z^JNt}qRyj*;PfvGFX~171Ba`(9{a1085Bslgd_zy9KA2*F zcxRLWfQmmM-QCFQYI@vIL|i0M?h*)tR}FE zHqR-}RXkTU*8(tkKK>oAh{}?9PO$5e9eZF=Z_NL7x72sTQVZ^v)LU3ClH)v&Ied7ti*_t&?J^XEpMPcm_XLF2!~-hmpOQ9AsQruVHZ zG748@@{eW#;)6-6iS02c9+WWvSub=dlyRdbB(9{w$DEXkLFxC~8K!wO7en(4hHF03 z9%;Nv5%w?0&q7r>CcwuxWxY%b=mSYc@N=o2M+U6f1ad)iCj=uBXV0-TeySS5 z9Wk`4TA+GRN|e+q5U|n~=GIfz5p$u7=PlsRLx}C)cZOn!c96WMs znS)<_HV3mn@~CKB4<)OO}OSftj};0boe8;IYJqhRN<6B}7uz z>pOAvE~SOlc(r9U(yJ4z+qR^_%5vD7g|FxdyJky7e7w2+3J63wkOU6ge65Z z6^iHqvz;=Q1S8`i`fMTVqboh(gIUKv4$ma*Icl&2rwwowpAy~HOgQmL?$y$zmN3;1 zFB`maUM1g!`QNmVM+3^fy`i=KlcqISk5CF|VobORX-951J?HnT6)%UcXF-`}hgsY}Sp+ z*rx7T+k~a-tU@PyoLc}*q|P|+HjYt;-0A0UADrmYm(5j@O}sJUJ-ud^94`|R)-Oc_ z{@Gk#{N!H@Ex#({I#{dRCWk-Jb1e4Axr4=ClV4$HSco&u*uLI2@*IZP7i+W|&&R(g z<_OrQXQbL>;msIQVv1z9^Y>Db;Jc#D{8<>)cv)Z-|C5;baT_JS;FQ-USw_M9wzrJYY`$-h0pfRd*X$MN#WhLa<)#mpU{eIi&n?lK*M}F7=$61L)c&%1(~U;(xi;(rqSi#2LK7 z@bK7Gv`YlshrsZTvn-?8=sFebJ3xY#njloi-dULKkI}HRJDX03-nf#M$4k(kjJ!rd ztYS{B{dW?|Udz9(Miv{l7d|s(b<1H1daSiL%}0@HS(WcE@oZje$1{90qW=B2N+JdJ zs(X}KK|y$T_Ye5d<}jdai34YjOgq5Hkosd4VM%=ad>J(szh4C~D^L;jKT`d`M$vCH zBF39kB%Q^k>bNaF0z{Scy<&UouSXAY)&{dPX?GA_a~>a3)Fwse#ztIFm0~0aB9LYdE{w@_VG;FI_HSlaw`BeZw~9RG z4fY6p*Bl1{-a)PWLe!JOVz8Cf`^pwA1#SX|E?%)282eEW{UP$AinRT6tc4EV|NUN& zdF4`UR1H!j0-*oCx#g*kS@e#+|3wZ4bmBbPQq&EY1*$|1a;3H=!yhplBkiMTSI@56 z<%@~KZPPmz-}!141OS%u%3#bA0cw()t1K)Z0w+s2Rq0g;1Jm4dTYPtAN@)cIfJv4{ z4oNt}zJu?Ihj&Ht5IFe`iOZ--?7XCNNiO`|xz`bXN+Dm$60>Z+P8UT~cyhw9uNK7z zDfgw7!^xnyDxYv@W{(pKm>n%1hf+6$9k|v>dfp_ zpFe$SC(Q(|CUVoxqn14nKZF0U8Ya1QlN!uKa2Ym=<#&|8-ltRgS;sSqYvAN}9QEnL zTekBJ@{i`&D7qhtin+8N02!wdh*mI_YYFQz73P~D`fmp+ZbdG3sv}4%*@UtqgPk@$!O9C z?6v{LP?;RJ(mozln`fO9IDm35YYxz?8W;@6X>jIvgYL`{*Zv8)^}7@tTvggtOE?V> zF^1Kl7_OnnxFber6sNzYK} zu$#K*uh5J-Fw|dF2zvF^^@~gqx+dIpRWS-Qq@+BCu`c>oo&*I_80ln=T=2IM1)*To zS~f4N8C6G2PTky6(T0CuBI%6T3Zh3keU%slYr5pvgWld6cb#klhP!u~x5SU%?J=W^ znJlqnx-Chcm9nyq&rdGg8nIK2IpO_E>T-)OLcez80S{5B{&m7gq`tU2(q?BG85w7o z-l&MlNON%_ZLQ$sV+s1w+s&}ZNiKHR z-#2Ty#}T77=-Jt;?+F^NClv>G5TK^IN{GzvZU1`uUU2hWbv!N88S;mksXra{85JwEfQ4q_>Hi#3=8KE=p`540@2`N1o5L(OszppCqcX zSdDi}#pGhfzpmfw9H1v5S$uJ1&s*1IC}JYO8fLSl;}vGyOd*FibbrNB!V~HJtbnj& z1&O{}G-X1!0CmS>VE_4DQs8?ap(VN%XrbcgeWge_J&yJ{xB* z)uN=EeDRadI?7_tYggtW3nNkd(yT~*O1%RKv6MdL$hTx8e;H2CO6S-nAJW=?>SC(0 z33m5GJ04u&nhupGB8Do7<2WZLhN!4ERn<_#`ED|S;cJ-x-BR6+Iy-4t5tjz`zsH~l{ z+q=inG2a5g1$W7pc1VN>OH?sjeSOc;w7L|@7bb!B5&c$o%T4j}Y>0>ZcaUUx?sZ>( z*%cBN1eW@nJObPAiqG!C9^}jsFq^<}a^pje9szoQk+;aldq+YH4+q<&RNar0xZJ!= zf{!LXl#xakWdx-wFw&Q|d@C@9jU3&(Y6o&m%GE(Bt(#<%V5XIv@!JH!itb!i=0=y5 zF7qrL&U~-BBA0wdTt=NPVn>=)kRt>I{aHX9oqzfAvvw-s4oHH&6$?WV)x#Hi-~R|> z88ylr_Noz`_qEE1udjg;^TogVgM)7B$36`MfmlS+2v!mVK7&rU#*kEb3vDH}99ly< z&Dfn$73f2Jy)z&*)2g#BnJ&Xl2|;208V1<(!E<}2MwrD{`Yq&#w3S7ct0mLk?LUv- zeuP1*$G!CJp{RKR)=s38gz_z0CwUWNoy6%=JGa-TcV#{y)zN{p?q%uVrQ z;!p6dW1gSc!=TgW+HINQfAnH#Mye$keO|<&AV%@z#hfszawUZdWGUj4rng##lRgDs zwyxm&o&qey-Ci8;O-oBtk@^K|r#4UIErsxUlzv8P`*u}|WXvPe{>^aWdSpDMnL}WWXjHT&`LI6jxah4B7!0u9E~7#$@6=y^GuWxN_k3 zD>HpfCH3sS!V9r!4zS^5>^9{;)UFF;A_ghJB_0X8s2c<4quv48sfJ+X zzbOX?T4!l~uH^2?)^`>L-BQVc>2Ql+Lf~9rE&oK`g!UQSu4RD~Vhm5c+)+=$?-3mMDEvxx1=H*nm5_=n0&1#(sUshECp4w-D<1C~PYp z;CkbG+Le%EqCpM8KM~kQ>7p2}P>6#w`Up|?oR^G$od_i$lxstPu4Q%9^%<4p_?7_f zDXM=sAb&@$oext4aQH#h(f|c}_ZSaKxrA=HXLSw-yA&cK1if8Qa~0VP;72y`l-q3${ozg4;G*KF!E_LvPZ}3|46SOUnsJZR&j5A#(yeeohcDT>rgO4c zfBSKF=4myhU8w)|y%+fR%qc1f5}#=H?tKv7sjd@Bm|kekE{ftZKo3x6$6jS;?`P$; zx8F|<5AV#>y(jWgj~m9NptA^UakPdJb>)aE$-yin+9%Srq1@p-c5Gnj-8LP)z4h#D znSt_pgbB;CFIqzm1DjzBLk6Qx1~vq7l#!+iUb(jZgh^trl33}*-0spzlH_I#TAzQ> zLXHyga3kKUPE8ULW4UA*M-8&Dv+-mGRr73_kxbPAY;i@m>DrF-N?EhQv!*QKe&)z+ zM@oKoQ_T5=*hj1LstmE;z!{hcqcCIspQN}xy+l1Fz5)GTmjbRO>gEsYT33!2%W zafjk9&Ov2X%!ZGGwLms74Ov?kBuVaukjH9W7WgZ=uVqvpZm9W(UHovevYDz%?yD$7 zLXuI>{|=tXhgLqR>x*rN5xUHQvZI~o&m@p<F3sh5@dI+;8#Kj%5{F2xY zf48AsOc;J&(9|ztHP<#Wyn5BEz?Gv@)O48K*bR+~Ee6_JibkTS?`ye|YaoNqKx>fE zi_Wv?-26u2_m7+^vnP^tr4r-7hUrQ+x_Rq<7#pvg zxVbKj;1db+3}VzF?g+%_ZhXFkhN_3QksOJ$hdJ`MN19As)EvnS8elZ$-Y~)89F^?~CFK7t; zxUU4yxZRb2Vc`Pbjw6FD9l$ZiIgn%sJgY_m{}8B)neZPJ$wo+NgET{;s&FC-X}O-h0UW#Bfa$ z>af}Pv)`Gac~8U@{Xf7@&UndhICmun7qqm#k?##<_56MpF?ThKr`1Acu%DFkago)`2;C=H@R zvQK$+*lDl5!Yy&dxBuHZJet-h>RwpqpmdbNL`EMg=An4UB*CUUC|!5=cJC7#tianG z0Y-igMxeE0+N;>@4-a>Ofc@%12fix|Stz-?&!c4__SM`Vim&<&Aq6B77=&*|jO8i$ zZX=SC!t#n68FX4cQW5h#6&(~}`zGtHAD0qdToffaxY&dfrXRJ!iguM&&>_oYCdI=S zq&?Tg1MUUr&H96%#qD%yd1Fa7cezB`G81emBtj;#ZX>@2p%WP|VX zW`J!BVciYlbJM11eQ_6tsy94r&leE|*L%PLO<6p-zQOBPTtl)f{59Lk_Ra_jOM}9E zgru_ZIqyW7Nh8zo$=kel|Af@JQ;FTX0KFaCZ*8tm=^woLK5}t=J33zZv+RP=Zsr7Y z2ySSJW6y`6pish+D}LdPlibYoho=EX!TT;b75=nE-Ozn>(Nq?_e!eGU@|B<Vx1Qx@=Z z5z?PF3{fW5&&$4jJa1gMGntA_jP<`Wrt-gwe0^Cq+A88W3m zRzG*Pfq(WbkZgRcA)uy2IulRu+QuR|Re3dk*mq@HP0uXdUULtu$-hB5mO{C*#uXeb zxKW}Ucr!gHeSJ*f5RaOQCuJ+-<^jx@&u8sOqnwE=72g9=yF&oiFR$GZBxVQ~HY$3# zFJ_wOwwa;Dyxn~|&W`)>X|SOubiQb3K@?88u@B8^AW4NH6J2HMRlrYtt-21Li`uP| z1(xV?$mw}LPf$%B72T#i_)eW@CrL3Y2+UgyNcG#;smJv? z^o<#C_p9%ctDy z@lhLA+nJ7!L{Mc$;bk!?PvR7;06aw(8&gV3Cl_jL{CQDkn9(Ak|2Ao*+m3{mor11s zKsW#dDOy(F<`dt(>#(nheP2f&EkE|0=g77UR$FvDEoU;dlyBo15=`x$=e6S_Vt1wn=gO zEM`QYiBJliav8q6tNc58{KSXpPtnAmzCJV6LZTu|8EZ&Q{|k2d`j^S)7a@|P;c&`? z>w~bP1w7I0sLxue5qV0yy$9tUtqWKn^=kHJd!HXMS4g|`;dTH7ugQ9Ik}Xg-Y5&E6 zbcHxVx1`UOBXiNJF`b={9|j4*6lr6++mf`tQSf`$%MP2a31+8iOCd%;FnB%}POTxw z7ZGFwNLgafpUcUIlG9Q#k1m!gm-{K7b!}Hs=1941GJx0VBdGp}bA&j^Ma)VZmJmXs z*vCJE0mR?_?&HHrItId?{0X8{owo%B1%$p$XiJw9@T9BaKOPZC7fi&73xic+y zmJX|@*-;kt!}bdga>RBKCy}j>U+aXsK*&wd9AWKRcK*tu7 z@<|4!bwa|D?8pCb{^cJX55egfEb4?GLw(5;afQnJt7`?LehFKUxm5fz1Yn1HGBf-j z0^)B<7F&p}MugftStkk2FkTsj@YEohOO_0avF+od_8k!+A(6FC6eGH8Riu@uX#HLm z{v!{w$jE)QBuU48^Hb_eaMA^MGJ=$!$)LJ>>NH*!umqhWA?f?p5KuPJ#so=u+r9H9 zN(smm=!NDUIr~etJOIl2d?3mxx5uI-2kRnhh%n%A=zUjl_m`m>dYX_$rIumZS%kxN zn4Jhy##WI~I$UvyAy&QTr|VDvaYy?u$^IB~z!w`>&yR=f^%j94kF1eg$_t|1=|x{A zLu?^@eyRxa>P7f=_~K#hJZlH&uKTRcV0pZexqt1nF#X)-wm*bQBrOazLJ*U z#3g>&lOwy!if3hoE5WDsh&3SHnH}O~$g#5}cOhGYu;fDWaM}J+P((K@&?L@Ey`Es8x4>+2V>woeE5TbNJ&M< ziY12n6b;8vlNG;;lvGbE?r55a*1|YcJ+A`tHa*Q)kJ1+2b!-8G|M-=^D6fY!t8~qm z9tqXM@rq(*j84crHK=?ih9cA#$}Lc{*wTW-j&b%K&MGAEKSiDHc^&z|An8u@;kMX+ znlYkSfWMq++Ev{32Jiu#ld~K@RFk-rp#5P&=L&YLX!+4<$#0x49=SJNbmiLhx)R^+ zPr>%Oz-j6TQre5=131ly1Au9_66~+SQKkV0;aG@|xob~dDmS6nO1FumRsxZkea&;1 z6PePFbt{1-#jbU9VQ38j*GhRNj1ku9X2n5njPS*VU;NFQGpwZ=nd4%Pg&d#*dCzbU zM>a0z#(lXQU6YYIHCpppFpcdZ-7xsGTj}b85o%{lk;~>eQ~I4pH#uu=MGc|8Fc>tv z!Eo(2k|DMz@zrn8$O=l|&I!p73r|hunScDf^Cs46pq%X;zfu@&_L{FRWy#Jxs*`lQ zcxf}riQy`zmin~tP2LnWp+a&ZWy@z4a{)eL|47c|+sQ|~B>=fF1<82b3)xy9@{hUn zq6g{T?30k9p!7wjOR}K!))S5f+QGr@??n;W&g_t`C6MdjU}HBIl~Gb0NLP8X8ZQGi zcYph}!ughtw{jk`5d3$edS8xTQk#DCMe`bjPeJNHf0S?zr)egXS#Ll4+h*s$HG+Ed zQ`ad)-So9+Pr32nys7?%+&-qBhsP^h_^Cy)bUb!P`UrAPOXIw- zP-n5#PyU;XHA)|+le9}_aR5y?>;nyl=WeHTdLmiv3NC&Q&tt<9znESY#_QMVKtxGM z|0Hnz#}<)ourygrSq|Z2_gLb|bVj&S$YF^uzAq-W`(1UEN+02cXIr8WI`Sw7W;KH9 z>G_zp_Ad!Bo^kvEv&&sF{^yf23zrXwe73>zycusEeK*k@^-z5m0lBp));u=p&69L4~$a84cfR7;N2e36UguZ9Am&adU{ zi8d#`+IaGKM;Py&9W9}19|1e1#4ZvXXrRC?^}B?<8qoaVwwq7Or$U|*kc;vxa@x7J zq0QcUS+eow>E=)r2tcI7&>{ka+UE+OA@`Lb{yOJy zAWchHqFa%ZkwA(XpCJ0aTG&(i>BwO9Tr+@aw%;??{#m4!9euuS zy@UBox|4)CRtW?25`1-$dZgivszv3Y!m42nj`xJ!vC0=6(On^&_juQ%7i?w;V(=dCv1Ez@-JhNMVYWPJX#$`KS4-guVyV$0~`&|7rmk z*0{m{MZkLJ{pCG{cR6VB6Xx`Vpk#T?Ix97ZFdv5zUY0G`FxLqT1sG$Vo+D`cA}rD> z366v%;2g^dq@u1C6^pc=1NLMea~g^#s;_ivBgdb@v`_rcdg>?K8O@}AHZ7Qq3K60; z;872E8#TVS_V@K=D_&a@TL=SV)RmA!jE7aw2@+d)(#FmAgTzN+|8B z9{{(ePJ0nH*hOEt{XF??w|5XbZ*rDtsq91bRtyR2Fsil zK9KuXIVAgV{mMLEkwGM-gnN|Q-i`fQNfBkHwXvo2lGW|N>KQE zz?%8NuM7rzQczB8r;UI;`^@#BHt9#HXno&b3Ya@%Vd44tG|jw1Nq`?F%oC+G*S-|7!;-t{EJaTfDydp~Tiq}%^{Q1U zM`#|=_*-Y~6rkmlo4kxb#`LUD3@=C>V1Jr7T@(k>Lt00sIYo}0wHJyh|hbo2+r5#0dV3S z$-1~xUU{(g`!b)&N-x+Eu$05w(?~q(596fO>?|d7G6aUqO;`NE8pXzPJg--;FsSrf zNt+Ba)|Ie>+*myBaCW|Id<#>rSjk%e*E&p_bS}ijyohK;ay-+2SRrYus>bHm=zCtT zcri1_a&S~)dZzK ze8UbCNOQaIG2!`lQ-=Im+!4ws_Tjuh2z^Rb=fi|YRukul;R;d5dB43{-RiO|2|(v^ z{OP!XI*hnWnA*yU;YT_gK$t(@694BW-jFw@#mG8h z_Vy-Yh7-ZY73}@)t!FIp_@GQ-QD>BXaTBWLH(94Ld>Aq|$>tcYg6(oRZXzrv@q%P7;^GwSR@T&eqeqQKHEdw` zi@^3BYzUC;(MvMZQjlY~%+ zk_bzvNq{VAaw4>B207lZ42rM7JFzcz1dMK9r69RXJ~g9{E+kRrDK~FI zX6`d)yH_M)KLy=lv5CsczKIe-xQ8%#z+X_tVbRUi`-ey;N5ba+1x@7A;yWTK-a_oP zdANEh)j-zk%@klAt!}i(xVyym^>wT*S!w(FOT1+j5jh#`!=?{PJOOdRPt3TrPJw(rD{Wv`tCXrHwzJY4u{F^9>< z)nyPcq8>?pcrlNhX6$HIWQ}mxfDeL6q{&8#L7O^fam%nPn`L@t z!1&k`D?T6BNB^?|wAWbKYxmRAu}(vp9Z2+#_E>%XEHw<>HI6vOQP0PR?~swv zIZxp&pnop>fUnP)i`dd#2jMj__EI%*T}zwPIuX=^33D2=udxrHH5|61kQ^~lxRxr7 z9g#pT%#g!SS3`a(_y9hLs?$VUw0)ios1 zj}P_67%>}SV#bu%A4^Z$y)omb7frin7{bdRJX1H`GH|D>ivU+mMd8yDhiL%mEc8X5 zHHU*i0i(<>r?lV5dVb=DOL~k)(fD|qd+du}3OOw=25616+1Mj^qbz_-r~hAKi>0No zBxnnYzIz`KbKT!Z|ELk7mK5BvPgoKX@`v0KtZ^KrgW6s9m6D{d$0=Sdc{$y3Ui-y? zUld^+!Hm+WH?3bB42Wf8U_pLuCncvAL*0y1XappE$!c5BTtK}TFT3>UH)ip*C9NF$ zo9-%jAKN$IA{lkABdZ{{`R#fDCK4j{1^#|IT{eZMX>i3gF_{1U>&91V zrnR#!ZfS?TW5vd_0T;QG++DJg5Kf3KUSa~Jod`-_rgR$O8zvQ6Kg%K3-m96Y2b8}X zi4`h?<01ahGa9z@i1*j(8D(fy3|`bcxwdTXf5f*U=#r*Ohla-SJ5*V@eU4ms~o?Pa|4! zg)F0*if;kOzrMEttyg9}Igy_zx%BGaXGEH7-dw&|Y4#7COP|$_j7svSL&KCQxJ}BAvQR+VXfb-4p zTR@3B3Fo#k-FNTp#1W!A+?^LBGGa}x2m8zz??13$>~zy?lv(_oZ5_!nT1W}# zIAbGzaq;kcBk!aNKNM!T#~sg?So;GB02`d}zohy5TNV~FVYdq4peI&C^zOvT^RONH zV8o?VK8l5|3_gld@TBG`p2_-(mltsv&hFX&w(CDA+4SnH?c^qE`;3y>g%FxcM;@;3 z6xmV`u&F37W>LcmMwga}amPG??VrS#RKr}5A0H~prUQCywYO>1$G>_N+&zHCGJPZl zR|&zK+bvPDA#r*49@+^plR8!ZtH?W1G!}mTCuVY1`JXzb=~+nJJ4-hqc}D=0>d$a@ z2(FHqx$VfI`%m1GY+vi~TXg>sM*lE-tVRbHKI^nR>lK$ zHDmFjtHCY#EpVz^o7m-&Jc+P((Zwcw_cKjM_*UFq8Zq?7m?==IRMOL(r1fSU{68N3 z=$2BwzY6m`8!vuFj5Bp*s?F6}Si}YR+vlzvO&Ei2utVMhe1e_kG_CZ^v0FQ`mo;U0 zjy?Bu%C{z#gz`9oN}8x!HRF+s&J;ie!^CZt_fm)K0aYF74-(#@;83Ut#V{T;!)#cz zSYzkvj)S9y?tRk-@ReA3zce~W?CcQuR_JA4%u_pcGPN4_Z;p|S+0@o<_WX=ZBun0N z`1Z=Nd%bXg+SSd)LLgFapua{d(VHul@0k-hcPE{o2&H#_H_ODJ?8ic^b39v25uBbo zLRMN&pAP@YgYJW}t51Ny8B>H~zd}>SRz;-cm-rt2$yLT|J2`@h3>UAfXi1|>N_7k$ zl!={xw3ALxB1mOKMA~3v!6#}tBpNxLFL25V#Roe3%m42q@bI9hWx7ZHg>f(|tPOR# z;Pimts|sit!ey5P1P15t+AS3kR8!#-x11Db{!efzx5gbZ7cMTt{I&ZOPDO>En|sGd zE=-f}*L%RbekD5?_J#ZlV7WRU-q}K|>A(jb`y8`DD+W%X9-TVL^86do36IJ2z*IS^ zo5G~7Wm)yhgaqI=%;XKILG0h0ByNMyER%vJgduzPMnj=+a&7NpI=Bx(m5Z*d7)<7+(p{L&yJliRz;m7)h91^Kg7N9Uta{Y(asjJB;WetM9)mie&kPXOlO4xj2R zSTdp>{(Co^Jl4hZ!Y8(lLhN@E>#a9=IV~H-^y}nvnZ_hsN<~pRICL#o#8H^{{`yXU zn;$3%daJGkL#OfTR>+rE1+qm~gQ&hyYg$7+VBr%RI;715QqQ0q@d%`KxbJ?Ekm9XR zNU0(Ne0SjEUpf0Rvyi37tX(W$3elCQmSI^HJZ!(^9>^mP=oppS{X&`}wkIRMIZR)h zEa*}eZa>5|HwQZWY~pW~4~Let>MwkbVPB~-2s=$Kl~ipG^^YG6he((^3gOvC24;0O za!5%Sh9R+;^M#+#PMqU z`s;dQNm>%cZrV8Uuplrb)qB!=eIe~oX=685yO*hMbVn=G4d9yDeddzA3 z%?zr!xVtTtP3a&3zhtdtDC@PoYEn>o@Kq(kIX>^bXWtgD1k|o?AYk?LXzEMZXPxZ+ ziEUsK>n9sMawlDKmi1gfK^yCY z`_Wx>%VkQ}mFs;-=U%c}`RX7~Tg=`x$N3C0Jk)*}?a3Rgh$iwHo+dnZne}*le7Vw1 zO6UhTL7VD5)Br63=6+sn3g_&GE%0NZ zKm`2W)it`im)d<5`#|t7`+ge|FOxC=poWGEXk#G^`FnA^a_Q#A8>0rE#Ajd|kijDE zOdi)P7+cG=P=F{%UvcaW(XG=G-D*khaY9GB&aAz4{C& zSk@cs9{goe*No5fB~*V;v?-H8gAdh0j?**0!3tsKT3=6rM@A@LdLwq(JU%>x+EJ2q z`Fm3MM1|MKgRSzf)RlH)BTd~SxxJ9p4%vL)`|xRT%jsEqJZ`Rb_v{a0la)2H>L3a_ zuEi>F;*c*tun}Z|m*BYG{b3_cT3RIKS|s^6K96ANas5Wp&UDC5rNxg55f|x!zXI24 zYMwMb#qoO~BJu{Uq3WJ4zN-mxt!tXK53(q)<;sQ@hfK}T(7*{x_4m_*^d`-vo(NLT z*cZo5HAF@CqPWo-u{)HmQZa8YBD$KrWgrPm=MUX|EJDqG72a{$s}SRuaRm>7lQF+Z z{K?5&u0ut{v7;~ZphnF9bBb+90V46b9+3s0qM!tRwptPzTfpamxcTm@6r-x_UeCd#|QBVO+7Sy|J^f}z|G z_m+)qz?PaeX=CiDN6s(T6>>#U6lnGPP?AZL0E9w3w~_rcsQ)7#r$=T(rA3maZc7Aq z4zS8CLQe@ybqI3VlNSkxRr8YoJ-YgnbIXq)@LcZ0}7po`lzis9dlOuVo}DdqWi4+Pa53^rJJWpK+|CF3q|sVW%p=<|EW+S(m$Es{xYpGu$ciKBUwrn)-q89QT}9qp#sqnV4% z(Av7hlCq*#q-A=gPv~QVU)?;tO;1n%;+}$)pMUc?Pke8>$jsWa_~V29pDxacZmL#; zF9+8SE}9=y=(5Q~7m}ihyfW7j5Jf$G+LcjYL1U>!sLS&7srycd^p7KAeAaX`b?<4{ zFJIRE7{Ni-LBo*gqH_Mw;Pz37d$d#e7S_GM5wg6L!uGF&_+LMT1b@oARaI%wjW^Vyg$&B+l>5 zrBhMMV?hm85ldDnzH5``$OJZ~$mcoUk|my>zxph<5n_JEMt2!$R^{%0=9&H%f9f3y zxUThC87*M8Nb_?j-sj(wuV2nWyJa47{4GgwiqC*ld3L}@D_ysQM2)zGKD4W*_OfSJ z?Ng-UHP}(1q3fbn0qJ$gf?U5&lQt0Kv?ZQ5mY$PApY}Qh%)Q(EPO&U~QjT+?Cofo( z|H<^9KfCxRnHUv5G_;G`&8S83>=S!1DU&GPF@ zb-&AJwfgs<6)iM||LZ`*`>w?k)-^qna;!~{fmRQY>Qp(-Ey<^GpC^0b* z#^!$ti_sjLqAzIkLWzC0EnQ+c*cs+tdI_CFtnk=EoG}ACcfRarM>3Rv;3)sBz$9ux z2;je}|M&Q*orVj+a-aTy_^Xz#rti_Tz5D~mu%L8}PIev*#0n`D)q3*)H__o=l*J?r2$CW5W#S5FX~jpgmUs?ewN2=l@vW0dfc(sAK^Z^ zv9w({Jfi76P4=aakz+p^;Wn?N*2#X!GC=RBDUDc@a=UedpGDZ+re+XH-V-M$tYWmKwwlbGm~j^3U@> zW+yML`-Kl;DX3W^gVKlJL>jIQX1txqjH5pm_LFd)(2wKy7W(z8uZCx5g)XUePra5D zP($2*m%=w$lcoivN(wv=e~&7y{vvHcPI6;5SQ4YSjM%JAO~_E=Nn1E*MzTo5!(VY14nHh20-L_XJp=}7~vp=XFwe)un$iz_5 z;#wJv=zP|rUAYC{Dqqy4%i?HjGYyB6S2y}LZOyKD?&ZH`H$W6jNvUG3=8U_WCp<>G z`pr*n(-K0ckZiEavbiGYA-kR`G|TNL|NXmKJUN;4*xTvoLc)XHp{GWYo8X=5tGKQw zxVhxF%G=l1-#vI+!l;8GE33tS)^9y{|7{e$tK_O+qkYmD_#o0nc0FM!&&O!5>I(RW z$M3$!01UXiIRA=_9Hr^2dK3enj}NLY)=r`V*b?t(+T5qZHE`QrGMjE4?JU&Afa3r) zHTj15b6Zf{NvSRc4O79X_ra?dyK$|T+s}$A>FyWq{026f z?#U0T?-l-eJKvM8)16YNJcswb;Xw4E-zO1F5i!7!ZQYwK-LE7T$>N4{iS2CO-eWwD zvyU!^2um{CM`Z`@+^OLg&uogmtwrL@4&EZRy9KAprdgH8eI%&7g6k{Ypm?N34plUy ze0o8K@+M~1wWYs!5-|JiVNwvyySw1^N2Nd#z3}O?CkH>`UWawmhyrzT&=dQ}nAQQ7 zbjYiOWi)DaLy**5rt0V(G>AM6>TsJy(9o?Y#LS&7S= zFE=%RkfmH3&VK)tg81;aI!$1YXo_dl(0eFY=YJmI>Z#%hK|1WQVlIJ=Dt$?Y)&8wn z5$q;D1soObc(c;bV;XJv~)`d z!j=vZBn6(?=l4J7eZK&4ueIi$x#kMfg;_7B1eR+UVAXu|<;JS8aP;!G4r)ospfLk3 zz3CoQPY);f-c|E~Ux`OfiCj#F__m^m)(AV5b*hw+WqZl9_Yu9L^>;0`19bCD<-T=Z zBd~Cl`55A)RblfPC+!kRfLd(7h0u*`6yPGUJaKgXjuY?0#Ov?8tlc^q<2=!UTAiIT zZX67YhliJwCA!BaN8LG_GkLgjMe|C&;AXi$yuJ}mCSs}T!2-UCUCao0D&%gYAREn~ z?8e-;c&rObacrv-Qm|7w{zLa-4r>0@-1uGN!Z|OjCh7zbXNx7TulM)wr!q*Z)B1C# zNT*ZgY7}#-+xOE>^O@Pt2`Y=zX{X4Up$Rbmm7H|&G{%JRX7K>_f=9bb+0{aAQi;Z6 z+V*vd@E5?^aia>+CCo+!bNBeZKOJ6%aZ|=%<7m z_xDs?blq~&`we~_OaRPrg3f?bNT_?Yzgnr^&JM|p@In?v8~RB~%}5HqhqCYFB4Tgo zbKBuzbvh}Jsc7uH&g7d_jmHnR6OMy+m(=9Q2IcvrGecu-NcvrFBfW}AhPdL$4)2&? zHSG;@Y#gtqH&XAn^vPGW1-|vCzhGoG@<0>@Z1P9{ase1I3=I5KfOvt`@Lm1sMZlqn zf7ys$02HnKFd+4N(J&ae=d&r}tEr^-g@J6pvFh<%emm>p?PC{+Ov&(4-PmuL zPn8nGSY}3K-gRZo1FJE9g2^($*7VljsFQTl&};}rUB3Tn<&#E=Bl&ULwEe}n&3YG>0)XGhj01*X&&~&v^ zT;}@X2%O@77HzEj*w`QEFW!*vmOMS%swX=)24Pco2yINM^TJabm&}EQpi(?PO=S{twQ}AJ`>q)ZD@qzQNHMQz>6^hT3N0Lh$drh zn*ZT3oBqUzYFwr>S8jW)aE;@rn?=r$;+=PC4+E$?Z16!lY-eY(fghK6XUjw<79Nn# z$Z^Xm!kIQlc)pHEe1m7B{V80Ukb+$)dMehtQJJW^o#s*|Jy6u~@^yu>Z34x=fJp0u z@0!wktk=2$&h)~m);Tx?)lKO#S{V^l%qr_0EJw)wXupunD!VV`MZfUeB+n~MsU zrW2>u6Gu;2-(`sHp0eN(3NfHa2~oK>$S>+Y$`cC|u9-FvH*N|cQ=^s((pA5ljcBmz zXe*YjTa1+EzFl9(YWu@WM3~bC9~l_(fx+0 z$g>EgjEGMeu7Ie5ujkA1aAPgjxQ*?Cc{XTN6BEhSRM6!rocWC$xC7fz{qW19G`u4B zAta;B&oBs2awSttkFmiuePhwkcQf0yOpcE?TE+#ITEqNftBejwP_~@*mcF}lXunms zqjS|lmGGAO50B47RTLHO7|_{QI$PO!mCL?_$# zeZRue*?ifCZBZFjrM=vfIKh99lbLSQ68tmn^^&_VpxCwPd4FHCbr>!AQ3ZYb z&FS`XoRE*M4e?XI-}rAzfSSeChNIn@;N_!)zOP|B{gn7kQ&2>SArF-vhC{!Z$BQ_3 z^@W8j4Fv)uf9=L%4@x`yMiCO;{HpBUp~rT(Gv^zuas&7L7k=UjRpebdNU!@ruBEjv zZS3muDqh}%mT=z8h$^6rr_+<;+c#2rmZTJ+(1_2>h=EI7SP~5oU6eek7{uO{bMx`z zqTrZ^OH!rLNI)h4bX_E5vhBdFl+?J}*;YoE&2{g8mon+dVcc z`6vOeJd*0G^b581b;mQsR$1u@YVG)3<`aeIxoUYK88%o=s~lv;?SJ-%vfdgp7MAq% z4#pOd^1$a`Kg=y!pLLN@@$$xb-1&!+2+HT8A}Lc&fimIAi}ssBQLNK5#o4aRmU)%# zw&A_R-~DyYxA-VK(lT%W@DpO92P$DL0{#@I?tjb|kG@)!#TwxPWZwNRTY#0n@&oac zMY7u3&M&RU>{pa4KgjHEw5zjm-%S+@9aO=h;V0iQHCywF&@N4se!Py80u(*L_BAT6l@-}JJX|?J!xN%0EdqoIr$&|+|9D8 z!kT)ADUNLaRjg$Hc)zo(M6oO)_OOTJ%9~`;M2=BSH6e;hpPl-^@UnY96gqaao;biI zug&8fw|BfsE5aS8agU^M;%aT=@t)dhy?a*Mp-FtkTlTm;N7F=Zl75I7f1Ey|mv);> zEfwwS)+v-rRN6!D+xleB&n4#tlBCC{|De zp(&t`k>Lz0D=I=8G@V@2)0!9eKI}34Y>qV?8^?^KH1WU8jf?DA1?Gn$(N_Qq{Hv4t z-fUHbL54=r%srr-E2_n_AZW1t{OeQxF*{cd&ta;iU5?l)r}VcxI8x68MxNIbKgbSQ!wdsw%N2St)?o_i0}VMUNWTlG=s= zf${gX22dhAN;fugx^K{d)l?PkhA$yEr?kDQoBhEm@WW>7o@2`+VFIw92&x%K@V}fm zHpx91DFVEQhQ?+4=5XAQ@8Bx!l6L_et->Zd+Hsgse!GDuxRu)KhO{$yHM~QzHHCcl zwL(?(X_hplLd#2E(`yWb(KYSm0xc0-K>^0K3 zzBZxklE970coYK^8KMt*eUr4Jg0MXL~L z-CvQI;*9(3Iura5y@6%v&l}iU!YD=8xJ(;iBAOx2MQi^)5s!hfD7Lt-adQWx)M8KTE&e4SzoS}=~^hv%sh+Oh1P-+DneX5~^BGTXGm9@t;&WFYJ#CFL_@7oW!U zbY9~%#)so8Lo*uO_H&=FK2=TZF{_`VDyP+QDuw~GSf5vxp%crkE!8=qy3!wtVhnNf zJ7J-L+pIJ4+bFdW1*c3R|3izC8p}s^i<5ImB8vF+^~;jrV_`hb7{`5+5p%x85GBKz z4+wAYY&hA&s&7E;#ZW10ru*trZ)dmPqIc}trPN2yZQLGSIL8Qe%TcuLdk+WqqIO>5 z+~VA6yPyf91Kb}-^YR8YjXYcmYi6A=nJIa<2c(zoN|h87nHj4x=*AD0wr|hvOMc__ z!H6)KYfbHB@Ik#?ySHO0G$0H(_+2?GO)oFSx`lTk=8STMq+q}4Mhrd|pO^>EPNpUOt>e1Do%AAZg& zc@QXjW?%M~Nnj%3W3V2P|A8W9-`E6JB$b9_CC=Em?uXuWq30fcH430qqak_4Mzr|a zM9=yxsUmicKTvZkVE<+x-p1LcB_l|4yBl zsc71Wo+~jD7gz3avor{J@{2Atp7|V~MgzP1YD8y2jn~+S{x@PIHugz7@5Y3#v{m_5 z+rHk&+rQhscselZZF@h)0T#_Ze(@#1^Vg&x9oe|1bK$rnAxnp%%r@MZBK|cW7`eGX zP}Mf8)J$4%GCkBx~O}+`o%d zFsf)X94C-I{@ZryNbybQsXDG)Y3^-me}Ut?^78zxSDX*i--R?wE^OA6n;bD{G0Od9 z=catjmKQSniZdS90wEkASx)l3rt8F}Sl2?!=6k-zmV~9xEz$Sy-|Jq5ZZD4vK3jBR zFS`UuyaQiE+mOahoYs9(aE>-fktEb@x&4SVMexpclOqJkQL8rkO?rO5PugAFBuQiU z39Dq(Z3ZvH_l;=R(3g)GN~L_}tD3bX*>9f{wuFTA;%3-%iCc%$XlZL_5X8@#J2SSl zIOX3{>AGnc_W)k_X+-&{Swl?3onX1e$@~H=u{oT-=Z7C-1K*yXG?J6Ari%<^za_dKjV#EoA}wNjkKzCz>87B5Q1UQRFmK_aF7&GG#o>xw__G z=_m_@7Lc@=RM{JT=Z~7NIIi8m7THP4ixU}5 zz3fsVDX)TNxr*W*NxCFJ6!Ndil`fhqS}>Fo88+(>siZI4N7!nFb=&lR&C|BS`txk{ z#uTVonkTIn6{`m^Nx>d2qv*XzN|uf{k>FU=DVC?TXB=a$*+=AJA{|7pc5z%?3j%As zz4y)DFFXq~9&ldYNV2K3Bl8_D!I6}rm^Qwen4oZIQ<~?FNsB+2_Var1EQgGIe;q?u zg_;A0L<)L9!};$iJ3ZKc(z^bdSH#of?9a3%KVeoi75~A($W!M5rq5+MigwNMHeHVQ z+>=7gA4_ie&)jl3s7%Jcp564@A*(LX?mn}+h7tk@(l|T4pDvsdM6))u)KZRlN9&k#o)C zueisb@sAF&8l|(8ytx}zu6CiO4gzYwwx;Amo$mK!Jg99*U$>o@81c5$mA|N$G_>5;1lV;5OR*>!1PTHA|6kd(?Pu8t22mQ=GN@_Iek!hPaKfm1(Xo-pAT+^e4U z)qh*UX65DICpN@LT3n>qoMIwfDT3zq2Vquz7*9vW{@f93$ z3pO(|G8tE?pFeBI$!gX?y!XNv(Y^p&(`vd}7&Vh4V z5@PI&KUQz)EUK7yT}n&Lp>gq!;KA;Qu#%3#3^te7AkwRBB|RF=3VQnY%i3tXj`)Me z*>{ap8o-Kxt8Ue#-R8NpzbcU}P)8`VSATdQCA%?E8BUWab_4V)45*26mf>YXqi?>N zy64jRW+YT-ZLH*f8!{CaZVHLpn*hmOIWNWiF}ZDQH25f0gUQ3kFn*Upqy2cq)x zYgt)VlFO7x{cK%%$6DZh7)6^h4zjp-j8hASowk6Z&6+{x+jfL!naZ6sZiS_hW72q1 zsT|rvLLRz2mH>i%;$+Vv(1{@_&MmnUP|1F{B2*eh>b+_PjVLT1D8sg)U$ zUp4$MVV;#4ZwqiI_zcxZ#AdV4q=PXiIR5v5)V0{=LS`a-hebq&xQw_t9wqbS;1)^w zn)+TAg@A>KIPi~qP+P(%o!RcLP7J1C2KO9->B%${@FjK?VT-Bq@^)3+e5EwSL&r;g zTcTUg+dMrpBJDam9>migdIpwt2k|=dp7?c~dX&)|8eq??npnl>i558f+GwDc$fgR{ z3D^9sTwFeDzk#*F(xE=pJS=X5mPcNV6o^|JUT0&gU0C{O1KY_nTrtur{$e=aKUFZK zUj0$xXZdmU;Mu>&2POxOwq3;2?4;^PPe^RU4I?7J!#&eyto))T3yMkllcOLMNxCGt0i>8XtumE^i=MSsFxXV_Tph=Lu(#>aOjgB{?R zUi+0_<*70r-eg&hpu0`pr~})L;YRAsTB0gbC0x<0M0VZ2lBBW8(VxzB;wEv4EKe_U zA0$VSl==wy->T~gr_3``6Hq03z7=JJyEukG@7n$&lgZH16%&g4*N-|_r%+kFm0#_W zt=I{${#2<6n{!N&o*zEJ8A$*@Q52p9u2>@)9^^QV?*zn_&CMyOg;#@?I5neqO6gg+ z5*SR2Cp&q-XY%a4v-(TqS0tBHgUX~cO&2H z$!|666)KHt#j@>rov&{!nB#03xO`crS-zF-s0jG-{iIy)Z>AzfcE0g>e!Mrw6sIBL zH26X75f0WzmRRV`g#^60n)oNihv_K~&$@2m;*KGRue$i{_NCSu_Exw!=eCtc6mfqm zsw|v;W$J6-m0462hNu+1<&2E0k+h^3x>m(iPpI7po1M=D;H~29 zjfr7fE4%!28(2qgdo?Q!d=9+ha$bDYN?s-sB7f4F7s>!T^3yF5ChNz#1=qUQyql18 z*3UjFVL|GlH-EiS8P*9$rKu??*Mb2&ncv6=rMUT?vO}8`lm@w;qEur2aN?|ElZBwQB1VfAEm%Bvju)5T z$YB;v!mFY`Y@45t={tYL+~-?SVf!DR(m}z%+glsmBoe2>8UmLf9oJ*ru(nZyC{VUz zrwPI6yGd=)tz3RBQ45`6`zu@rBP8Tf+X+{5JEQ&gRuq7KI|B<`QPb1i%uYehRXyx+ zHO$svb%YXdrR|>-M{~v5L#$f*y+=oG7Q=NwE&Q)08kJWyJi1%b;+r`7?a$=K(@H=h zm`yb_${(#891@~nG{a0C|A!`&=@EDO>8j(s&DW0Oj_Mll(*Y5@$<&U^LWq=^@8-&U z7LuV^6^Gc}ov!;hl8^GqOV$a97zqXxHPfBvCL`{8V}ql~^Jh_)*S#2I=r4}vS}bZDKWVRTkaa=M29dX7neqot zOdm*%zKT6J=lLeeCob}ic-g!>@lbZp$(qg*OjZ6pK|0H4Pfs2mig%wKG#D89AKeew zDJ{dPcN6uy`#$p1KJstluAd=e6AoCRVJ2IuW551z#=AI6aQAe2gw)eqgOU|~j~Ffm zMXkV8iJpoXT^+s;5z039K2Q*d17!tVDBt;3o^=tw1j+N0CSez{>Kagv3W6=)KNpG` zR4r)>`hYbyq>EXz!G(XhN8IQVy^w3#xh;Q-qhoft1)9Y(5;WBj&+;)Z7Hj^ZttHnG zmyONf)y~e1v)L*ek(EzmJ(@fUs9Wl%N$DDfT^`26^4iPJ2E4?`{{C81F#IlI(7;~IPc954#J6ATZy(oFLc3FW4hop!i*)fl)UCQvQSBldL!f802 zr>ils8G?7_(4epAazga)HZilxAg zz3!H$XQW(33!UErCUhnHlj$WTsxu{Om+3U*F-<1_>{I*I-~lBzLq@A2Z0EyOki7`_ zA9SyDFz?%X#gjdg#l~K1lSvDNx_F!Y+`@|g$Lu2GL23S6a%d8Ii|O!2!YjiQjpO>v zZ3A`VQZTH_Y5{go#{U=8Yr2Hzq?QK?cFQO6IFzQ$S~gVx=n;(;=nivJzw##*g6EO+ z#V6&A$3#IvfS0VHda5;*J$R>ew9RHcr}kC-?y^V>L!L_)n+lW*gK@C35(oW#K6Cb1^!uD z)Tk9~vG1ysm$EKyfAem}$RV>6jPc(+wvK2-2>MpEg_nAW|4_e_RLHPYR&&!-NyBXH zo7x!*P(Q+_bzjhIgb98^_3TU8ck)^PEtHT!F83XU^u!Ra7sU#qyCalwL5Et=ySVL@ z5~8DAqw=P1dE&c6jKzQ%zcMEff)0%Vl3z5p&?a zvIX1JUbm2t-v^wX?eI{p7vdnt$M??y_VW&I&}C2e(nteLm5PGPWc6P?5i8Z{!SJPV zn4!MBbozewf-dU)(_V5~#{Gj{DGuoYCTohuf+ON|Cr8FZaVbUPNa#i&QX!3&>rDyI zzE4yF>2znL3Gg0Yge$=!j~Q%PZ$XCpLkw)}-b#}O;-jILeFSP1tqIPXA5Jr4#KN(i zDY}b|quEG(c&xO&$aSRim;PFlM7T7dONsu$jBnc=v1n)oAksa5NGDL?47h<|AsIxg zI~?~VBRyxMDd5V7=OcsP^xYD$S6aT^+8JhqzTT?Nc=a{;J`+=lDq4Q0-UtHZ3pGlZ zXO;|8Yeh!x0X`jm`kk7rd(9IdpWKSFfiv7#r8i=xPZPQO;6d%- z-?D=Da|W#?^RhzutZbp@^U&};!+l8K@{aj^&#&`$|8fDUOCx2ZSUNHKRP6@~D&j4a zaiygVDEmRL#FP1%htektQY^F2T-{*TW?0+FEcp=0|xT=Wap--I9Z2*r#}NUoSN-EU; zAfcm2Vf<9f2c{keU9=I!+d}ND6Y^hw_e6Hz5&#Ac{Gp}s@X^s=3hp4oQq3~Pfv;@3o9xuaq5pCd%ztJN9Wb&RjbF;SbzXk# z`GCU&5}v;dQ|Gk3>AY#G=$xzl)``hRmqel}th-tq>eJGVN$_4a_@#gH(Y_dK8eOVPi{oC%Qy?6mKj#+5ZflP$6M-j6lz#UIt!5u)~$ z%doZ~@b>cEx!aHJvc?S%36A~5pYJ0}y@2)47P|Zo*Cga-8YhUDB2*3XB*ayTa$xwu z>`klCN?(0g(K_?4oGI(B?K#$UNz0&w@K_W*(k4={$MO*m9cDyVZUq}W&m?q zAa}DhVs9^B8C?5@9B#yh5*3#VGSsZU2pfl`pX^2IqTb<7VZ=2GTa9`pGEf z#qMfjgYezC?gayw1c4KUy5<{AHX-2aYG<;1fG$AXF2{9rv{tYr93qGijt) z|J9H{U~8Mr^2%t6UZsnfzf_Z2PgDjOmPDa7;=@G%t<94ym*oR}L!~dW{m+a)9qsN1 zn*!sj~v5&Wklc|2D;lX`&z z(3_L3DtNd?Lk3m&kflcY>*4H#gm0D0N(jog8$-_Rzqp>EdbT~{Am_l~mer|g`$%Vq zM|+9bJK#IMi;MVTx)f`GgLH#;e#`>&NyQd*pYs{xpBf}RmQVo9Zdg2tPdwii{%p}i{L5-8wc!v z`6aiXe-U94cYgyYK^T=4j?9U!S7KbCECr{XL^q8maq6x90CeuiLrWjYM?99A^Dh|$ zOU)WadaYXs$CNoaX)H9zLV+|bsE!8L@Ry2yC~7Gd7~ho6RJ7S`@9K)xulgOqjbd=` zAUqir=}Ms_2TKlF5k(pTc3foE@nv3=Rh|0MamOMa2#FMlkwQpM2AF@|%bSa7emi=? zN;Tv(?0A&)FEgPclVv#vmG zcGjFUSVanK+idh0IVdsKp?}~3T2EncB8S>T2cvmmvB@dLi(>tgC7|&6@29;s0o6@! zuFP9VSMc9qlW$*cvP%?BW9xOAp$R&C{^`5mp5 z#g30gZ3_1B;c3G_gwA>CIJbIssNe6tW4Vz0A*xKrgA5HGgldTXk1ltWLuaI~4IdXS zJ~YlJHhVA7O244nD^7Tkeh~p|awsBNCqPn*1<7mY*|sOfm0B}1wJervlW2QKHYAdn z*uBaJ6W14kC`s!PL;b#zK^5mr$6!c>yu#O&0yp=Y7qXAl;jDjC z>b<#56Yg4v4HiEX&qFdSqrl`StG-}RFrfJi3lhnKKK#W!S{D1M)QK>p@rc8&<;NTS zT4l5UMW814lLl53{*AYoe}xAzvi`n3Kh#NA4%IGSy3Bv?U3^h_{;hZK1kU#;C?>?a zzcEx24p|S688j^!`@|(i4&wK{(NeowiqI8vx(GaJGBSv}kMf?>)qgwyA{yUBwL2O_ z<2pB<#8KAD{=&%T-FZ8#4=h0X+nl6o zsV-qjNf8)euRY02B1YOT8e+N=pl&_DsQB=P@QU)UZ_78WK@MGFTNsd#yhkA7UmKI%2< zo3zJh0v-utk%P7FC6p~CR^QN^R>-GNqAgh;J2r|+e7rKL&hs-7k_}vZ09vLy2~q4i zuN$~h)nv$_O;2NtG@$~HI7=kft9W+z(X{9C;3Pm( zz4CmbNf~rYAYAYUU%V7s>t1rCLgYj%8!Kc79J-ZYh9?=@;IJqVaMPnUnfZ0h8rUiG zh>?#Tu?h%45WP~?laq%G%zA1DMu~9>%L<((TI2o%*Uup zFkXB-{GhW(D0`aPkYLgN$4i+Ets2+Nl%*V;Xo@4q2`jRovWaay2$Dy}OEvbIPf3kV;Cd&!s#V ze@|7}e5ZXbd_dMf&0&9i@e*9JMg6p5+S`xX$!@q$D~eJ>6Pd_?ooq!6qy%^d)(&H@ zdKN=o0aN5Oc*Y$cQF-g`%QTVj0nrJc9zIjkpr_|#jlb0$V)#=>3x7(n3;pgHD6n0< zH?)XNK*hkzhrAwRjN2`}GL#cPyj5jPQ$^VBTX%mLU8!ziVbT&gQ(m-_fn#t?@i-#q z+BnsKgv$IWl%=T9sGe;`s!KxwvteMBM-MTdK}J@%ulbW(tl}SMOWBWutceENts`7# zF(7-owk-E+To2AT8hBXZI5V?$%Ro2hFD;X8B1MfUkb2&4wei@x!~(YTs6eMseEi~s zU!p&IE^K3^?;lsY|KEX+p@0Cu@#fOP(Qfh4mix=M;S#n|fZ!67SQjpJ{mck4aduYa zSyF6YmslC9DvvTLFV1nKl_DBb-aU2FWAOub_US2HWrFw((M6FAO)YGNl(M~5T}LQ0Z3;QL%lkA(MS z&jpO3(LAf0x(148J~U_7Dleg;U?0(`CtXes`5P)qJtlo-?(qY1^>TdtS5u^Cg5(Bz z;Y3SC-!lWjmwm%V7zo-JpNd1>gh=L72X2&KD`i7^aq|_-^^$^kYZ&XUU|$U#%;U42 zMbi=8<_xsR%?xVy|AzCIFjVv}lYk)Yx*uZ@5&!J-y@AAJ6;oqX+)+h0T2sMAdggVF z>M~Tnp8lQP5*nI=8~(H6q{}7{H2KUwBfIwD!*(uE@`ZQzgfFRb;#fj{02H#D^;)S4 zbqjZI{+?>~M*UuHaI}5@M1uFZfp-LkmN@yNr`_ zS`$9it2>4KDGaE6Cg<&*1!f@RNItEtt0Om0bPQ-4R3Y{fLTj+%TJp)d$>FD5$(gHp&F}nowHBr*DKp>xIlwQQ|MdP7=(}VX%_i zjHP9@;J!=juaEYf7 zQ?_2|pB`U}5kJmY4)i+Yxwr1*7)d&`ij4m{P>>!7nb$L1qU+L#u~Y9 zqPIp@_EsSMSn+r5I7lTq!8jJUO~V6GG^~HaeVh<)-^Cdayu3P^jdXPElK^_wbIaWX z9*CNoeP_mqzdFiDz?%fjO}tTB(ffty{t&0M8iH{_))+Tj*QmZ>Eg(%Vt36W%#b6^( zc>?It_Uxk5JqwJJ-?d*qkd#eqmUJb46A5INuCg5P2p_Ne)BK`Wu^=Rang{?a8$8`T z>Ah1ld6nbeCPLy`>E!JNND0TEeJcBF%N;u@={M{Y6xx|s0zZWTcjOrd95H-t$T25y zv3l2<6f!(EHZ%b}Cvc|4WdbDiGGKL`c!`ON#xRa-9h;5;6%OYv^a~6D+hXs$b-hez z2vDTOR}}qo-jOQ&beg(QAeryZtjTa*Bo7_9Nk=tQqcj&&-OA#`)jO?T5y z9*3+PVrpp_IH*wuXEc(d-{CKSI*g*}i#Pu}U&jY;bHl&7@;#GZsGli%^XvVNiC0wX zZBql@ukr)kDw5tMQs_#dm$2{*cOVmzZCDwrnC)zEk0J;ZS(8~F`;9stHYKzAMT@H*PlN>wgs@NM|P--QOR#+6b<{lx=(Fi zrf04>^W~*z+x_J}xafuTV?K7UJoJu_Y#lCo|5;&=7zwRYD@2cWoXxLbzvja|KT+G_m>guOITl+Z?^O6mZMP;O7yWJj0T>-{n3bPn;bp-a}ed;uSYERb)|y zu+;vuI&F$RN$Vtrz=Eg2o1229?4+zN?v3`!y-+!~4TO7B7bXg%49vtZ3-aCs zJu}%Y33MskIYz0WA;yE@m{;0A9$%yTAx6l13!h7!EAMj*E>U;fRu6}FYYzm0vZw?x zNCiQ4m97ZAd}a6vKA`%8jh?noY|PrZ;-=>0FBwpPWLBr;#qnNGvDll^2uHE4Yu%x; z0-^T7^w3esJeS+p#WA4i^~lk5FlF%t>`l1=C2*Yi$pqJF0GT+#6c_ZsnLOMaKJVW z`yc;DvmKpUJ@FfNoe6q*9c#Pkr8RDuZ7(@IY5R;j1zH*pOs%QFsp=me_@8Lc>E?n~ z_PBJBaLN-R{H8w57(822mWr!PlHwu##7G&dx2_fqG3VuMreAo-*yFg1z*$+=Dm}#f z*^LaE`&|saLo2x^^wLfVFx=L;sO3ETW_NIXQsKGBs~O!xVdtcpq*t%?zA!DWEDler zbL0znmHn=D0ZH!%kKMnk{WzB!bC zlf`KLO=w|-XnAX7IGmP$9vJQZ>$F&yL(1Cl^{K7p^)tb=3r75F#K>x91U`Oo(Td&l zjQ3SiXP4lbff1R5iXs7iXHnWx-oy-gM)C-AWqb6*MrmRKLi`^wXs2f7|GV9y4hddb z0KK0&+i@J1C}<~e@??pEGR=yH=OLvscr0Je(cj<4Xz^*fBZn|iBWn&> zDxWM1quw<*Cv}QxzIpJpeI0i6p;YWiNTt7gz_O#8Vvp0%0!Mby;Mw+Y5wemCD7bg! z0>%}wBuXI#CKep3pa(no1$GSDK$vWznQ9VVOp#Ou3QBdd?#m|taQbwXV(lNs&=tyB zk4MQ_x|cZk`=f4`Gm26)9@{S*uc)QC`Vq~xvBXp!oYH{4I@e4>ux znxYocoLCeT1}{`=?Kw#}bo4CdoPsloL>;}yG$FTSJbm*alU+ihZsgUPYP4P$TBCp1 z2fGlhUh7>PGW(kMV{Z}+!0r_(#rQNJOP%T}k|Q1>sdK;-6|H@CxLK1ah5zaAF*zNJ zF#4WCO#9pYmZSx!9bS^eOC%aafH8l_LadmsF*XE9QS8H7Db1$+&ghe%=jg0euiO}^ zZH$9$+*@vAzZTUJSA%>^qR-EED6U^;DD zBjH^68NXJn8*FaD5a8-_#+MXFQ#Jj~$>MzsjhU@O*XoZ47SY{)4F8A8F9oEfIo776 zp^tI#bRPd;E05w0C+7h}!@Fy%8^R49%Hl7nQy0Dt78>Sg6QO2VVZM3=qHdtnth_if zW`S$tdDo{9=)P*>6UjV#B}4AwbU>8!8YBJ`T_xdal(C_nvafHV>VQHpDC)OH+5!Mi zkiIy5y^R?pIGIgj8|@&D$?_vf}5D-3z|w%Z*Pr&v0WJ46y500R@lKc=V00$c-^y{4Gf1(9r{HzQb|g?Vn-46a&88nJ}W)+{TgmW(U-mgPFDBg zW`BAYIl8zM$KEI(p7;#4@u9GS1w)f^?}#XE2Us4x5F~=CX#X#N_tP!*_%Q=-w;bk=0=LKo&zl> zS_nz)idybmF4s2tmkYqzY2i)rYyLu7frd5E3IQHkZxiOQB((N0adAajat!Lmvai2l z+DsAQBpoh4QIK1T)T;Iuv-@EADF07ab!rT;davgXT1#4oQL8;&qnlC4B}D?aF9OZJUWG5 z>C>}yE}3NJHg1N@gJwz6mNg4^BVEh~^KLvpU@ScbiWjqEA{(gN1EMY~kE5BT!vA!`E>4liHPLo@Mn&D-z99PMONrh&Mw7A3+%z>z>R5e75>1ltGExn zkK~m{Cl6N!LUxHgSr9}-!Ic57?RO9=WtMQBWBLZDS~6IFI!nk|E475ehYv4UCNa`w zQt$f#hs^!6st4$8tCDt1wCK!dg|tih5whyJVdKU6PK)-F74TiNAtHV1e$2B%w;2ek zJ%3bKr`VJ8Juo{l@sV*;yu{X*!bC-m5%|Fqzv<0&buMZm_$7hC85UT_X70GR++Qbq zm{@38dc{;({ABd?WR>m1GE=WHw(y>|hAV;_kge#k zU@k64^ZW*x8<$6>ly%;g8XlcJJnoJ#MpLQq@+u%a!{)z@cB_^+w-Vr+=@nNjYbbTwmX7G`-J72x6+^bLz%aYCw+U;E(cXTV1$LfzjVMw{`vlLETJK3I zmK$bNqNh*Bj>A^KBvr1%CN##<>W0=c|NN{Ud&7z@WoQW|)Wgu<-6 zBsAIz!5HHaQG9R7=X@H7KrUJQ!46!pEU=n>el4!7a!$%PGc+1i5RkH=$Hu(ZLkhRb zGb~eF?mN$YHmR><+s0g(;{(v{HGKaL#IEQ=YvYcNR`eC48G*e5ChNP=J2otJc5X1d zO}ikSK?}t~q-!RzG|)|qd|M`JZ6tyBUyq}#c>;_qh}T{S=YR$ssoekzDtifSQ2S)A zm&sM+ex~uvCC$aSslm9y?t7c%)vF;c#UDQ10^viZQDl{B^%TWq90?0N_sdl-S-i6M zY=4;tl}V~f*ol;Plj`y9aVj&0s_D5at$!%t4zBAO{v@^2Ehvkz>H;h?U!eL5S7oO* zc`Xs4p2r~|tuu|J5_V{{H<`h=#sVfg#ZUi$bSD5apSRfu&r;_VzHFxvdQKV|+WC*a zj1#RDV{U*N0>3Hh^1^5q-Wz}IFS)D~2iy7QiLk11%!Vg!<+RmOcFgj{qRp^R^Q_~zKB<8s)ysb%et}8B{$V$v~OuITnTb1_F zP4hLBAr|{_XZ$Ac*UFzXvUJ+=6hW?D^B7h_jWJ^T#O+bS2Ir|P?`B8rNmf~K>-KluR*@L0=74rp8j>F=iy+OBA48w=?uaCh@< zcw#ux`sllF+~^Tnwl|$0|B5s#_PIAu#Md{}%vWAlwefiI!PjcbRFNk<`P0}pPRcKi zQ0wb!-NgxDnkHK)XXaE3AuZ332ZMd*^K-|jU;dw=iC=mFd&xjkd&!TM`Fzu_qdGHm zI@e-9D=dW$dKkyZRs27u-a0G_?s*@kLlC4}mX?+-iA6dV0qIh@k)<0}R6=Btma+h8 z0Rd?w7bK*lLs&q%yWWG(=li?ff4u~D=gc{C&pk8uTQ;EC3ix9*YyWf7w_bogicT{sVf`?@HPa%|1Z9faaDDgr>^KZR zI{*(XFl*o_>H2@cJFk3DY`5^k9S|E@B%0M<@Z<|Eg85l>idcJ2m3-|_o4bph$4?{O zrX1H*Fw^gBj*igIz49+(xR#T>SP9c(CunnI0a{Ir&Wnfru;b#d$DES@vH6M$;_nsJprY+iPV=T-@HEgB7MMzoHT8 z_+(6Aa!vH*{TFEzw_lt{bl)eop#&pS`bMgzlyRnSBGZ5@^?+X|u4TLeEaka5G(uc9 zB`bs^;-)=Cu*uP!^w)1Z*J%Rtkg92~;htiXgLElYBn7Uf33|EC3c_WU{Mb;1*B>8$ zX={vRa?<@wtcalSsm1RDCvPqRYApABoj$*QCHUu~M!1F#$K{6`yux~r}hVu3uXTWiq_Tj zAcx)c)zyDU7Ar8Q{pQJ$D}7mdG$F1xrqXzeRcfq`oZ()6RYK4eUsgd>{^% z9M><&fc4d?3*WKv(Kj}o5|g;o);5BdK?SnUmN!h3me*iRa<<3$*bc(hD9mUNBKF-+ z&b$k)^hE;jl9I=aTG|Go+JR?|E8mCnBQiXG&nj>bmQtcF_fngcoScA$mhiK!+7;`? z&NxD=>x=yXo57FDsNP;BU0t%P&AF@F`L@OEPi}If&Y4I>(LXEX97$g_B}5!kqUk`B zgAJK>RAAx^R&9w{1n7S<87+P}r_=9Yf5U|a&dI)cdccaK;LK~7I0_XINgUEOU_$Th zQ>Yemrd1_y0CkGLqUJ0&-A$ZW(;v<83DFm!?^Ka2Z>?*1JXm7B3meY4u=2(hTQ3j- zT^C9wFgBR)`x4O;}v#9TMhfLjDgI5iXc-`fk`P|bxJo`I2h*-TKLji zOiV4tB_d!)NB0dfKp2skfoq$b+=&bSb6*)%ce-su%L~-ZG!5~ka^jbk41~9l>kGB6f?`*~XSv@>4(YNtx=dDZi3aX>>_3pJ#ROR_!hFB1dhjSNdmmAVGq6wNYYUB8NCu-uGbR@1rh;4Aec4zbcBsE}#@U@yk zus4wNwzRZsv@xzX*gHv_kw>$R9^rm6%=u(O`1D*HwR68}(a1_$Am84`P&w14!g9Ym z3RER4gaQ7>H8pLZTe7@403M8uIUTcq8TQ}&?`hSHmD1#cR!JZyM&45w1aw4a9Gj|S z3FtuEx&~SY+}!<2!&YIkOvkk=2aVe$HEIv%@gf-C3)veC#|TjsQ=%}pyc3A)+brmqB;PyPzx^ok}_;(8xZ0)`#v^u!(#_{&5=z%`isp`0DcWPv`S5d*> zwPiV8B$$6Ke|d+&(G$3KIg&FXvpdS5*$OseUZc=|i}!lWlI?Ju$_O=A0|gTswb4K( z2xS90wL?kyI(JFZ(<#er>YszKeGqgfir4_RVGSY?CYKeYNz@mVn?D>`HyWjWf{pL^ z^FIijE|*n(3#w?7au&F@9zD>-XL+MT^ex}G#}}!uc}Qu>!1ZyJOA7+Nd2ZxBF+|>0R|}gp(M2WLPgxL90k#mk`mgxcRML}m4jQ7xb=6MT6?!% z&;X6|oUpq&R|olnb93<@KCtjvH8Fzzl>w@Fk^A?cYU(Ubf4?>jonn@%)H0S!g$G$|2+8u4xYe5`-~r}2gWTITET zFMHG|uP+=hIyx|I?P`y=Z5m$DoGH=KVIbf9{@w28s;WvaEb>a|{`>8kCEUF|y>Pn&?~p%5oi&=D~<0ffz_g};yFQ)2lLiO_3?-P3UO#Gz;N3h=|F zcxHSao}sV)p0pA(qOaG>NDJy#lxmcxYVv`q6*B@VC6=rZe#WXAzjmJakmY?Y$L)ZC zhjq@D!rgt^$}UBL*PpAzs7_D+L@sjj+uCA;hS3Af!wZQVX(|Qx(z)t7BR+{4bX(;> z-qW_15P^nAA>amKkB&MSSMx92NK>1TiMU?p<0 z(2{5}v7L3stI~(hcPA30rf5u+QNpr53i+ARw@P2x^M`x{f-aye8UMcPOxtO5leWL# zusBXh-z?+hK z{#VWuP0+f(tS&FXrCaA~&Vi&ju}%T+#~z7S6#N@F2kxcGYv#H5 zWZrAX!E_-TI*H@x)~7Ao%``a&hlY+gIjSy}mtO*Lf^-QB(k zKkd&t8QHm?{rx)hplh5nq_LLny11xKm7yl8q+GZ#vj4-?anp^-f}n0^z-U{(&d^JyJxJf2+<3OUmSM*n>v zBqH1tA%D4QkttoJyDP>ZZXP!~+nu-WphEZ}9MrlO8Ro`cE&Ut~li6;Tr+Y;jMrL8r z+|`qO?k3sResC0ulOdiJuX^{?Q<0`Aeq-`QVcV1Vmv+@5jib5iKX1op{Jx=Vd6}D*{tV06 z#RypBQ{Efy#LII{jOiFv=1Vb7nCNoS_=qS?i?;vSY7Pr;k?QiQkop@vnUSe;DcA95 z#JonOF9a!Dk1>iv{@{*mP1tM`)`ffAm5uT9-Dr^~o}SY~K&P?ilk>A%N!Sup1@fAk z<+m1_o*BpQmR8|BhuYfP-$2&y06X{B8g~=P1S%xf^ zgEL{cfxd5;<==diG^_<905P$#o_lC@Tdxzbw%2rccz8P}i}8y^R+l_O!^2r}OfR1j zBgI{)Um6v+JY)P*KT~W@2L=RieoZruP!&C~GovI))Sq}rdV5j+>fxM54THNHRFb&i z;BD>b=jO{2X1}>CM1Ma-&(-*yu4VSiqO!Z4@nIWVR4d0bG%foB_+P`CeT@X@wUAsr|~Km3}(j^?@IS9<}r)Z7;JpJ&-pk~5k`}&m0&6G!a{7D|Al7; zqYNH?0@%Uyq3iC$zxz4)M?iJ%A*diI`pt-~E&aKF|EVJV-LPOVgxYXCIpo!^-jSR7 z^4Zxp((~ixt$NkV9 z?0uiao6otF`ilH_n%sUm<-x(pPHMBH-^|rKKIX+R>2FmwXO-5|d3PpZ$K zwUxkL$NFwD(h5b!bzHAou`R7zseUc``7GP5hfAIi=Q(ZQsoisjA_X1Nq5XZKlU@;m zkYy40u^ahZ{Wk07CuZemQ{s^;17jC*{2{DXA+kdtSm8*xDx6&G+htW${XHqQ44ZjX zRI2gt;ln$X4jCTD_I(;{eG;ULujC)Q>tqM@#}9-EQ1SC)m&UNpRQJ6i64YwT(}wa{ zx^7egb@7Yuo7IoMRo!mk4bQ{dB8ugJioW(dDLbKCJ;{2#%P?k#?uX;eONz0_$Fgq=kioWp>Y% znBHR?oaYMn(@N=CUZ^J`hh_ziEw9ejTiT;ft|w&n|9dx2v2={xCihP6Ip{tM{)Pf>w+Y9HY%m=@n97eZb*R^gkoY^`j{uj?#D;! znQR*?EQ%LBN1H7l9{!Pzm)j@)>X9=NV`>%=A7CL}mY)ri}ug@t$U_s=WPb(|mjZJ0m1{-TZ?d(*#@?)9$UWi(C^I7C>jmjsM=2 zDH#xCfUO?w4aSF3&RreVc+Q0!|7nk=xZwu|$HrbAH(y_3gvWeXu>&Od(ac(sQ9OaS+NACo^YmVH=IkN`kZz=3Z1;cfyW zKE~iZpfIwxT_+t-7Z@nq++4s7%>9y^tlcUpRr7MlptMO^&ezaGD=s4YtUQnzKW?U8 zStTv)>vpF7OYIEy5S%a83Q9s ziD_g!SI!0qzi0?~?ZW$Um5@e%#ntyO*Tuw+?rKWAPO|502lDZuYy%9EWzUNXu{t{s zJQk1A*r;TDF$4q2c4oHM=71i%|DO8%VVU2`_ufYqw?!p>dai!V9znazc+=7&*oyqv z$h-s}38tkdlu&rua&RcZ>Dxz*K2T%K=E zt!kaL5`+GYgtM+<4~xH0)4e7cuj6~+GDhn zJ`jwDPr?Yk&x44ryFtWL)o$1r#H6I3%F4ETHs>z4{1&r=wtfJ>7~2?hyztx1L)pxX z;l>$)4!Q1tQ*XZ=7-YAO4Rv?EB^ffAgD|(SID4U^&^hX>^}3E9j9h3u{k1JB-m@5V z^7V913a+#U^Nos)#7WqLhd^Oe$~`}4r0&)f6jPom=1P24(xzu0SomT!6!46bYm-9e z0Tue?%XZV|U6u2#VLa>dDug*ZYlkl{A~Uex_z4O1ddzospe45(&1>*rl=kn0uG!&R zi+bDXfUAZ~i5bPspX-EhMFK+MxVSyK0*Pf(@>GHD6TxIiKB^Dba`zUoBA@I3^#aVx z%q4Wh&0WiVbQQ50%4_kbJy+6`d$*US2(j507z28De^)*j2*ad-=+5 z>-E^*=iz~Gv@+T2>Xe)-V*#T*U1V?-)p5a#D$skIJg~Cr-Nm$wjJ99D z?f`6zDJnVB7JGA2vqMw7%D0)7a0|NKWCY)BvL@ox=5nNa*VtHpt1}&PJGkZT>v{6^ zbJ0Xq#eh01nR6HwXB z@D80XpPabiVrerMGTE~8^&6!wf)SFKJ2R6$w}Q6yfAQI~`lb2vH6UbdI*<~>}@#Bg7?1*Ird^bcwgv|$mz;f7XF5x#Ogs({n`w#aI{2Y0n zRq?J)u!J6b5%a?I%id>+t%|1=aHb-1G(kBLCrUQnf)Jkm?Zd5mm}zqCk-)g>Ke`i} z)Z($(zvO*=MBR59r$vr_T+;m}dN7l*K(;mkl8;mS{yk2uaqmfWQ4uQ&cXgYs-MvB< z+J6uX27Ff#nbL+j_RxwY#;lX=|Dgnz6R#$|%PW*^cQbQIAgGB!yk1KmBi8Lx z<=6(n_~cSLg%IBE4ql*O$!7MOxjTOTEp`{J_CXp96=M7vE^L@>jgv#XLCxxK; z;*kReXV>~V=PN&AX^&j(htKyB(|^Bw8@i>}YU+^xKmr@Pvqm<=v~>F(D#10c!MwTg z9tAp^3tZ;AjH#x@%PX1|o!*E{3+1#9<@ptPeD}KU?DNV5$H!|1eSN#zn{$GRMqTj^ zzByV*BF^j)*JQDyjY@dvJ>Frh1X`wKuL$O@Dtn;IK3=VTwfO?F^6KBy!DCh(^@y4i zy0ummv0z;mZ_DrFQ*rwv7;cbJ^W{Pr82!95G}OB`x3E85+P|)zLQgIfe(Rj=uDRwsP)_}i7~7$1xX9tuNx6*lrfs!nq`)Qd>4C@8F*=*%}j zkJO58P<=>!e|G|XcnX;D;eS;fQXg{ujpCDXkxFmxBP83=!W0hBl$YXKGo2F`mgZ4j zoSyF8e#n7JSBDc|Qlbf1BJYqtFf_D93~=4V2l=TYEWHzRQ;jke8$TC*33Bus#soJc zjuc0Ix>IH0mE0{jdxlUVgeF?j?ELWUH*)k_4^b)ZQR6s#htRvm#$P2)QQj*f@90-$ z16SW3W?d~y=n>cNs;nQ|i41=E{E?EXqq!!i<^jKRu7BM)w;1{HjuNt{DDk+N9PMog zef=7zrm;|w$1RP;`65SnL~M?T*duqYy8iZC!MY-PnW$hv!+jpOUe&u0)A#7%ee{COBzZ- z0LvKN_0(5!F-mPP($LtLxs1R*Lrgb?=&|jv+1dTZsa;*&5pd*~ePqaa*xS(&>2bmW zh26HD(XeG;s11dU<`mJS_d3QD)-PgiU0P3%B#kJtk{!S4){co) zE)~{778PpDSXVWeR}QVUx5G@qP0{)DcTm-?bKuqQK+(Et;1L53W@gI>MzdnP#67sD zqQ#~nWwcskUw7im4t?w}fjb+M9A?$V9FfTR!4Y&OQS`J}9|Cfy@Q2qsQjWM(lRoIF9?$1riYNX$7Ak%bLTI3XeU zw8ssjHjZi=P+mfrz!L*xMwX8+)zgR1l_Zakq-#iJ($nr&#dH>Q?3^F}5%*99>g{|^l^W1DH<$d!LksV72oyZ)>GKCgkW}^c z*MqtRG!vuMef-d^`5*JqLQG7{6zH_Osufv#@PbX}s+#m{lCb*j9t|RXL!aW?V%_Ly zNWK=MzJ&OEc^A8EKX};-aHJG&&4c(d!v!owQRO^)Sm$Pz!H%L+YQKR2^n$oj&00tb zMYTsxu1R7Eu$^`aa>?MoNRi_lR74rNw&7FiNbZ8Tw#zFb_m9DhQq)*R(D~jfY%5_Fe@nzUxby6YK=b<#&@~|#42M~Yy!fc_76+=sda}mE0yjG_2EoXpfiqO- zqow`AidtBV`TeN1!OD-_$H+=v=vFTs9rLtzV%524xUrTQa;n+NFlIf3#PJ7C?URo{ zRg05GIH0ju9Vy~iP7mU%QL`y$c#Vf2=+_j^-d0y6C|9xhYa^{c;N^Ia=$Rv8*3#4F*Fw2OYWV zZhQw1&z6B5`sRP(L2d=Do{k=Nq*~!rjqmv&nQrLuB94J$Rc;2H8J7wJy{(L>?OX`w z-n5sV0%;*cLQbHAh98!bLevPk3W*$#-mCv+y7q;-=qU&c)8lF5RWaS_Ak1ow8ayWJ zawb~_>Dxu{d~(@0UwM-I!mMJ_B{;PO1-+bz+u4Q-`oF0>hiwB)-o{?9Tx;#qOiiLg zsN-JBK}!n=PmaS<4@KR7P!|E*LK+t*T$YwV>>fUaFgHmL<~&U}3*7f%t@_*H0(Ec0 zb7EOjMr5WWiV3mgsyC}M*UaEOICH%C&KyeXKeL{>F5rw0?$mzK`IS}`Z7<)$hr3w0 z6ltrN8@M7O{WK+hTf_#j28Skplo00X(dH=}MDUrJibo;amgmP#G=>ytd;3>USv6;%;xDSh!N)`bFN!8Jb#;Jt_<*fQP!36@qDgL9qTPTGt>9Uf8#m zz*ceFy7is3eWQ5MngjIWoS>Y71LZ`8uK3VVSb$So$YTqjg67wd{4vrUXc|crXP}a5ic-9MFmA8GAsE=HUr05B0n45mKa<2h;-j>VlW)=9e=X<#OoxY6k~Rb>)7=rQ6Yw;pZ7`cUo z-nyU0v)N`VIX3c#*Y)+6GnP~svzP7xTC=D9RbB2cPXkQ4=#Jhod8Q^2!d;sFVA|O1 zA?C{4&J>@B@Co$HxpdiDy75!|LobTK-RRH7wvI0QXKK%uU-PLE+8{EsC_Zs;=(T%m zAZ3D$C*#k2?5fF_m^u-R!;1t@5sb(@NUEgg6ILkb9i83(a>giRKw80rVv=T0yel!2 zbQ&V5Cd%U_RDjd2ro^c;tc}$Ff%DH@dBvvYE=f)nneEJx)j&Lrv+_^4{qEx|@w6Lc z-Ol@1Q?DLZO6+&wK#=Xll5NK5X~3@11s|ABSIHn>L9v2~ z4JyC@p1~Sp+~1t2^gHMcn4Fp>Qe-CH;Q4l#)xyMMBJ~`yxIFi=!biNQ;UCe}-`knM zD&=+aysjC)pY#c&A!?H!`}%SN@YiHN3jNa0zkTZl&^G|bQLkTHuRIQ|ujg3WpNE1j zI|tla3NCi;t^tI3NaMG3F^W!~-H+xDR8&%7<|?#=aCa_L`rqGw=_F>@yF!oncFx9v zLPVGEH_RH0)ve~CZr|<}XTYtUFj*=2{Fb~t1H@%*9nB90E7~$rgqboc#l?BcWREjO ze?X=DPESQ1dM?Jb07e@u+H4sJwZA$}Dx>`8bZSa4k0uSIK4Q9RtcOV6;)9IE2H%3Q zMFS(`-aiAf8w1J3-}s61s_{2QcH=xyKoFUQsuSHiU#C5gxD{_m(%E&A zaVX+?#4M1w3W^&azo>Ek1i73$T#s{FR2|@O$8zTy$0bw5v_umCTaX>At5}auO5imL zIS+Tp(JpiEq%QiwL7q_ORwp*)NO=Mz!sX5ePuA6QNzzo}a>Q7ljGT{>5()vER)E1f zC#Z)X!rV{ds{<)A72n%;E&scjGJo)R{a9^?ac(KBx~;9VrqO>;-bWC83U}Dh`7{i< zUj+7}K=@x^&ij<@9~t+8#Wct?cLSu0BkJ#Wt#VH`WX8H6)ZI>bme#!;e`}hqY~q~i zaQd(Dx3!B+wDrlPsT4jh6t+3MO$d+C3DGbWZ{BokIo)3l1&L8R_wNzI3nXYi$3U-i z;YYw~Ose#eHn9f(1swPu`>*k|I-T^N-aes?S8WIX}`3!ADf zgDn)+?NMO(wWv8BAREPifCo~%>8|QXY+~mvT--f{FY3>8IizYcfIYcN3E=YQbUQ#2 zhWV5Lh#s$AH)*Dkp$&~99I}PNa$L*lU4_ZeO&4|r0Zsc^{^s zZ0H%X$k0i_zXn;Zt&G3=F~?-zJuN<}BzRv}nz1TAF9C(E2R@26&_c%U12tm#lL)nZ zXp1+(e8Kv@2r-F9d?6#1u`su7F45=(Gbj1v*N3Lp zsQXiBQ>y?`LHFGmgTwI5c7ud=rI9oWg!$7CBY%dS%jsj&=YEI`sEHj3USWM-$$lL_ z?9|znOH#&#+MHn9=bo8a-u83m$yQQ9s0IW8%r{QEleLY(d;xi6&X+jZ(LqN5zdn`6 z4m9@QyL!rbPM0Av83=(MR)w&uQ}=0zT@24> zS^{{`vBu<=L`KOw%~#u7DFehgcnkTT3vZna#-qo#zqg$nfs=)mt047Pq|3~T#l<`E zVIVTq)*ex|ySOYp^!FS*3pr){_b?FI@r4(}3_XYB2bfU6%8X|eVwQT8Rm+#q=cM7-l!Vvs6g zy`EtGjfy%ToUGPnC4+nMGvy~LeX1A**vl2ecSFtNtuI{9a$Bl+4d<;l1-j`}dskI{ z2lF(HofRGe{(_gtPOhL6Nv4X5?X1w>MILZ-essD+wAw!Hj1ghmwX?hV?;1#21S>*q$BL9mU|PfF&%>0DaYi0E6#sqO4M zLBC_T;ZPWBKFcw;=<$FvRz$SzRrHF=WO=z`Q9Zw#gd^2ru2`X8QbkX%^rq4)m?>5r zDnpEAqKXf~iwkb+r~w&z+%g#{30T8wkdO7_vx6Y>w?j(k4>s5udCVdtPYOt<765cW z{uxSGK@PTWA9~bySe*fy(Q5l?UNPTcEguyTk?`(Lsb7gj3s|Na0dWW~EV%(;mO~@# zga^L-U-h|VHNcv7tjVbeuAFZxR}=wTQglOjP~R^_MD~d31Mju5mx=s_G}P!lwuDgw zx&d8eB`Jr5v*or5>mJUz0dn63k!i+nh#6L6!o)ll_teT1>kU(En4x6!+Z`bCo$!5T zJfEWBxUnT@7Q5m4a<}&FV=bMZ3r!2w$8X|n@z<%DQ&IwRZl?4fJ%YS2tN}^MKQazH zHxK)>lZy+~+&~4bp8nn!c1MS8=i5JSqdT%E;CT{v7j6p6 zh%NPcsZ6tE;Q-0Bq}~23ztYQ4O(KAr8oP1g-f%`5HtPZD=%*PM3g|qdgu z!OQd3tL_itv|Sw=8^rH@;5oj@3oCL!$T9q2+y4g?Uf3&}4v(Nm{gT&&yD>~ze1S77r5kr_e@=mi&==jnFO z?#oc1r$MlaR*T8Zp+FM{vKD>QmB3kKDzH z)O+x4yX{(C!Gwl3wclB(o{lczS-cXo|FP}}mhUZiA+4=FxzIeI2ElDrdnOs6x4|zF zLyza}gZrtm@MHDw={1*pQZR7Z0bAzbwh>e7A2c`hVSIY0_jPh4;TkrlBywTP>z z7^M~Umjh+@{QhGTCt)az5RSJSm@24w*{KgLt&es9kJl%kt*A>~l>H zAX1HDzZ(2>wDE9om~H6!%-a--G~fwsUd;sX9yj$RNL-whzWfKs%3U5Ii?J}koaq2k zDmlVW9DL)BLJ%=-GFli?pSlFk!eWTKv!re)0$VSBqWod&F+$6$ve+*8KzE+V%J|wV z8KN3BbHW4IKJ(}AzzRxsQotSG+zrKGC66+5*C56zaS`lHX(~R@_}f3dKnl#YgjU-f zg+aG=o^m_mvvdp)XJxJbW2sQ46^$J{PvCM2C52WNREf@uDiA@zC2ei*Cw;WT2y^$+ zi>Ia%S8dGUQ|{QayCn0?ml9_2gHFA-0J7I)(y3Y!M(`UxkDE~L^PA)6t`rPeJimR#9Q+;5R`|RjMvyZn{@a4pY1aseCO?Erbxhxaj$# z2bKg$ogPg@WL{E&#r8!dpfr}?@ad+ufjhBa?RQk;m48iv_J)yzVDQbz;7bT@Rim@8 z#4JJZUgF;2eoomX-9KmoN=@ky8gD2GGU-1wPrxF#fL6BxKeH+TC>&>(z8Yg6XX|et ze#n7)MUl>@1>XEu#g!PZ`MHr$xjN%7Siu%TxidT2dD`0#Mcx+Rwo z7O5xTCVp`pvKWxGUWi1-Bb{()c8 z4NA0z#zJ>dH24e|5FmK4XF^YT)8bwoSoJZMh9kTu+O}Hj9)I$prwCMlT%E}@?@dIk z;YP=O2rM@@qr(lvZA-#MY7vnwK!q;EPF}ua&G&ly-Cwtd%RRgKcsupgMsk_AM-D78 zgD7}AXs@DvDdogk9k_D-Jzff_t(c8%9|V|+_2f1gl`0z#5*Lx+veH6oGW-vo;n~>0 zbJzZ5uMv$wb{(FN?q@(&Y+d+eaHXnxWVEm*z|HV*^b2vxML)Fl^Lw z4E#M)v9YvN($kU?sFt^b8V)OpUqG5`qkvSC6P0`WKXMNT+sAX00xF=kX@F@$_dwV> zb8j0I!A!q9CAYm=@_^f5elc^MzE=?WiWFP*joP|seoTEN4i*26@2G#FI2})Og7!!M zR&XMOcN4;IRwQmXv;d_4BgR!5LZ7_ybHk?IBd2#C6a&NRlc@^IgrEZ7i+L9~cdN=U zm6cn9=8D4PZ$gkh)xQVzB%-skYI8z3x8AHi#KIxpHJ-7&iCN(WTF!r)eoP1ln$b12 zAXNq7H$%KO1A_0!g~DB`B_U5v<^;&HU3qt(_;#()g9A{Wm05Scp*+X?8XLDZMVLCf z#OA)arn?F_lkCfQF`k6922nouMkEY7{rl1 z?n)f{kWT=sD_(Qb2>GQ1*U)Hjartp^v06!s`c2~gHm5yEf%yM=0ZQO#weLfVluS&X zph5vHi+_3N`a>jy6Gb{@3_#fxNRe>j!hiXzZ6cFcs(;D9&ROCIWOjac;L`cf$TY;Gj6*l1ph zJp)&&1~|US_*NHA?UG%<15rNHTkxa(*<-Bj0MebYu-lpPIkK^)(e+>SGX=@ftq>IW z03+ergrn?Z8^i+%~hH3#SizsJtQTWKGuqvfc)x@omJ~mp3+7NoPz+|o9 z8Q|89K?zrHAS)X$CB@tQ@goRnlyiBZ&BT}RTDA5o8-DHt!C`(wRn>@`D@xEP^qHpX ze9q$YO;Bu$lD6W=`H6AUeG$0D+tQ@*7nvJnke7$9SnK<(xw4j_hhtw4quOiUBWk(Zmn@;`ID zFX_ucWJ0~0>arJtCgoVkz(R}Eml&0m;2rNr{$tAb-M(*H+bQFffKrma@*wduP>Kwg zkk7Fp`FAoP9h*n1&wVqBQ$iRV;MnfsLwLVdJ(HID`~g~Rh+DhAl1oCZ5>fo=Ax>{P z9eC;9-r|P}fEI*s{}7|ZwYBg6`Xg-jek}Jnv7<_gF>0o<8jh-3RZJiN@V=2@cv&#+_d~-~n5~j#tm{B#d8pQ>Pr^>R#*UXwH&CVM%W22eRqytv zdb8@l!;F5INw`DuuIG~{5dW%=b<&GCQu)-n_8Q6^X8~qQ8nsyv)%4C#VqB?1_Ix%} z0pjy;Qc6s~I!$>?EKY5;c4XvPX+GkQv>~!i@&PEf`gN5hl9xb z6{Xc5`vctbQ5N4JxLHa!08ox1QwzzL#bz3eA)~J86^QtB6db@w?A^!h8<&BN- zgiRq(u(9>~Whe_MfU=!cZ+MgiB9q7Rl`dqenHklW9Ayn#SFs8TxFc*Cq zzUEx3`v^x$Y~Od(pyfGfr_M{vr6CUWMU)cA5Nb{DL6Z>X&j!hXRQjBfZ~eM}*YPJ# zIv^{3V=1lp8=i-GgB<-X-*t4^88cp34w<9AHcb85mBHKI(E5{*XB*d zp4f-)Gsw`^LfndV$&l2<#L4-CTVSwY`)yq$Y<~NOn%dF! z*gI2Gqcs_`HYgfj5Or>;^KrQdl9JL}_tpa&sj6!@qTVTan47S=7jbajQ(Jd=n;!CfC53agw4lO?q{ncBFkENkIX~3=&2R_xjr>-8u+|5BUm&n!ukx5otK@ zIG_)3iw-FwZFdw zj;$F-3K$LR%B9ko75Zk|VTIu2Om)F#Z{JRCN#n^)riYDPp$*=YX)^SN((SW@n76*a zKrcpQY;6CQD)xU~vn%h=uV&Z3h*LW{IuCA!C#Vq*o>;5qJ31n_@C+q`B{M<5xM{xJ ztO*LCj66w=i8(}=i-Qz+>z=*^e^E6c&e;Lv!#bYxC@r(ah*Gi3PzNQAIeUY~D{d5S zs+v;2Ni<@5J511u`P?}0cyzJ{=cYXN=X1I4(2Ot(wFt0shm+w{@zDWB&{0%91v@A= zb#|gXi4l+$KxHh1V%!pgC9IXh0@y?d;e{Bhpy05EyGCWnjuI1%`ZGPXz7-mGUk$l< zo{pTa$gBPs)8 z<7ud9Sgk^LY?8GQU84S%a%O#^)_bV*Ht?{hDG4}Vq(CHuScX*9)q9vLJ9t=r*lD}j zSqvDY{@qTEaDmqkgZr2e#aNk02-noy9i?08m#SfA`j3TgzdksMIelcdzWUVLr(3)i zAo-f#lNBBBAbv;1BciRD;1dsWnE>KMol~_!8SElQ($|1^=H<2Lk%j*X_^8sSw|7&` z8AMpQ@EtuQsL`3h{ZTSW$sGfBU}FWTEY5U5egodnhujzcKzk$wFJRVdT;o7H!DO-A z>1Q>a^sg0Ij55?(fE=+b&DDz=8$G@NEe*Hw7n89@9&RdPcJTUhD~-i*V5 z^#AWmXFlMj8G{+rX~7S^P?E|X9SC=7Au@-%SwMOB@l@h{E>NO4P^U(ZG*{+=dPE{# zo@p`90~j(R4T+1Gh$Ke~Kb>nj`RvYCb(CN5(GE7wmXxOaC?W$puF$n~jhi$#<%SI-L7dtwnagwt$O)c+m<&2iY@>ojhA04kqF!;GjXgR4^Zl7oYk#rui9Sa zs%_O^@w2qc_WV>{)BEyH70`&7df&xBv%`m{`USrgKtdT_i+lC7H3m`xL|%JECiVWH zZG9VO+hTYY-o#@c&)^5oV=H)io*fTQ@@(7j5_zPi+Vw~M>npfWviTG&XHl1Qwe9N{ z`_-N^-GF1nVbb1!;~G!*CWmw@G#%`SU7!m1Gxqlb2Z}qok1$E{QzqXncz;47TYS;h zp}RDwTjh0OUXg)D2fKCOSOW#>+W0qTMFj83(W3vEAP&em5xI`fm)+E$M;bRuz+Q13bC|{~n)6WKz3z6B)X$4l!j(h3sIqv6-aUa%X?#I>VFrmHF%rXj)mdVqlbN zJt~Z}m7${2LW+nnBmEV}z7{MmXL{WJ9GT(jTp4&;F%neFj^gKc60CEG9ewu5Qb2jy zBSf?FA@ju(`x_gW@wypyb=jf%{{7uh#Xb@Hx2$6`Zl$0&bJd%|51OMUC!YwQ^}C9b zAx8R(0V1z_K9i#}VPQQ#6U!L@XZ2$zFcpz0q(QO^(w!Znm`vDBe*d(Ek)^$>m<%2M zIlD;U>o<06Zh(TQMap}mwCx=tIy#Beq3$}`QOQ_ccY?uacZgp0%>UkH7qz# zpk+AgbypQTu7qiE(*jk?+!g=MPFstn6;JClzC6K$tM6*`fyJdascf-FIe4{iKaNy< z%JS%O(jF&I^gwrX7O1F>V4<{d!E&~VLeaOjw1j)<9@$iSznYURu0mmF z7w;w}cjCeN+ms0%?UP@}T!c~D4T{6oiAO!i9n5+e3@KvHCwUD(uN-p{>Y~#14Kh+w zAP0zKS%jod=>A)Uz7RH+qRUt9vH(-@uB>lmpeD&X&6dFMBn_zVeDqSik$OMvj)*E> z^HUqoe|0R?_?d{YDo3K+#--S<(cJvRi31>VQcBVNFn|Q0$Dg+yKm8Q_*NXgd2QvAz z&fnOzh+<@(Kt;uUzthii3!b^=Cw_nkKV^tk(>}T45JWx}P%Xr`J$e42PZR4_>>-iG zUqR`C%|@ex5|fYY011auj7wj;5~27F0GT&S^GuFBIA0+G8C_JRiW1Gkv)Vnb1)@=W z-pxxWBpZL;W_DVzd0pYSk#m8>fAph0HPl0)b)Z1cFEN+8EnEC)>Kzuav8nv}L8!Mk zo}JAW@`D1fhOt=m_1|_OV?gL2>g@Kp_j33tftz-Ct)M`3bx8$6en6T5kkOQwYj70E?`U^ykAqP1Cp8~AfS#Vo(r1JQf(4mf$;0XDDDRBbkkCnym zzV?2)?02(g5`9e0PcOU^dT9&osB4_>y$6Xccj7B3WFMTqKd~EZxleV!)7e(*;Ke4< z#O@0rp}V!e)sL@AO-+?WxZXw`C`#}=W58m+vnQqH#)#J9XEYPl_?$Xu0QZUW(}mSB zGUo~M&t4dXcJkd@Qf%E)S)k=T!eEW@BA{Gbv0uJ)kYd3>n1;3EFh(O^r@C{l)TWH4 z48c+X@6Eu3NnZeo#|fIxiZ7W;ljYpgG1Lkr{^wSPyTP&EYQNFMG%LHN zHg$M8HcHK00!NL4E-dUBgc+}qf@5paLt`i8wr%~I279?cX(?`ekrL>f?+hU<#EW3k zDA6*-G^ND7fUB@*J~;s_26+3#7YQ)}E_|-8=-Y)OA@^JN>MK@y@ArzrDYnu#5e{$**6)&9GA?upadI>}aX3p(f82!kAv3OH{ z99GpXORnTeNvi|_<|mnaL~a_}c?!V(@^U5hCq6fJWqsPh3n*HZ=5@Qnzo=VVUny=a zD=Jo2GuB-mzo4DYLWzb2{*jKD0rFm6)w}m2_bPmS%YbJ|z+Tnp6^zS9dbw0mE*(dE zd*>OEU%2~Wo>W?xlP<65T>}g`|C`FJJZUY>IiqsowRi4#Ccr zaNoAt5?U$r!^KJhQZJyv{Nx(f*4PYvd`d^p0PpB`i}n_)Gj`wRDvXPAtx_d9P%3aR z(=P+k1Hd#BBW}Cr33EX}K$)vkysM|!f3u8%pZ^fly$7I>)1m#u3?0nVNV~fnaBNd- zL82qLYs*o&a;x80!neO5c)qxIuhg_ird$BEG$!r1YHNULZztJUN>m?I9&?J+3{mkc z@Aw2Sx@}c+9rk`^W+`2bS8KiV8)g<;&LVHG2>yG&!my())}n^`txc$ZOqA8-Jl`?s zMBI3B!WY}qWg%zYD0{o~xA?~Sf!7=YA=6XCelCyj_=qAp4+3HF$7+lF`^v%T$!9M~ zL0T-n4D?s-FVFbI6v#)Rn_@lh;BRmxl`I^J3o!K@++_=?!Ej5o-aRPgzhku>?1xUzPR5Fmi`UYh9 zaQy?v!o$}N7e|kB^l=Vb8qgBatk!V)tlzl|0chucFKe)cnV~o3 zVt$B*xS%(C<>?-(-3?+uJ@vw2NYTz4fHKY9p5M$gaFO)Vg zLrc8hJbhY8i4G6%Vfvs>pH1t+q!L{QN?Smhz zTaSZ`KfI6!nh24{pU(GJY1Kt`sz!qW{xddd`w=5#{na`Vs&7)@`2t0@*@~CBH{IGp zx9YYQ#`Dc*r=XyEC`1=eL7G60sQj1rnxdlByQyd|K$oaTdOQ-Ybl_t-h>Ub@>V9$q zXx+H(B<*v+Nrm=z??Ik71x!wu%LD6Ch_g&L1X>&$$9;)H}dFTN7G z#dkN5E2)5kXE0(P5)aQ&!u1@QBJQ_8H13m2po&Y}7i}s7>Rim-{ztAqP*I`vzii|4 zD~yrqB-_fuDVMA&!>ZQFBZUCzleINq7?DKHkaYaWMo`$QruEN$lg8ndyZauiKU4MBzbhF758q#^|pY}i`95O zi;A6Zye$Bwf{TWRZQLATY0kkER~HyEM7vMlIC(4SGT`aY7fjm^AI-Y19QS3nyX$M5 zI6oI(lz6P*rEZZJy%9NyOQ{BsfLei(!h<6grDV(m(OHOD?M;K$^oLFpWH?Vl3-&z# zvcH~p$>WfU;i?H$!Eni=upL2_~@>K9#q<@>spdJX+TZvvfK(OoP&aPiimLcardE_Uf99XGWSO@=JI!M8MU;2n^eFnsJ(ll zoQbSQqL$jE*fN_eySDubjQfMzij}MK1Vo-^FhiZSkeFms3fLHsE!Cy{2O9U2ga2j7 zy+~S6{;(%LS$cpxoH7O1w3MeB+k`A3C3&A zz;`Dnd#LM4W_G1P6;LwsHhEee!XetzuzBlcEBdC+lzwJoq4j~~?xv=u(OXFXW8UZK z|Aa#AIf5c$^VjpSH<`jz=q0P<}AUMG) zhxA%6TMXOx*-J3R9rqab20})J&}uUSTy#n@v0rT51|r(S721tTD~X5*(3x?3aEM0C z+yk|XADdMZA_wo0V_H~TY;sYKPgI2CZuj-;tIJb(qR}dmf5Hnq6&F`o$os3Zi@(3E zR2Y#d>qRIJ6rZp#_f|+uIdx@085lUfRE@c(y>bgH2COBRJue=$Q5QZTaex1|hK0hM zT?50#ouWl1E#(B{|0@wpXIVRe%-|Ebe&c4sb|dI~$bHw;_ebUbMD^)?gl4CoObjMW zJq?5%m!1aYu%Ur^;qchl&P(974nW1l+)F7lS|PA+>`zjFW~InUb2-yE%oq7Z`N_(fEF>%yAYC|DpYO?4z7{iB{e(} z@jq_d5-5olbLiQXKT6Ge+BRI5E?JFD<<*Uv_#3D=ZoW>7m_u%sOGdC8au zW5}66ZWW2?<9Umhr4S@qu011pYFI`((+Xqsf#MPcoDboo{pv*NLR+H*G1}JQ-M~E{# z@9wUZ$)gb#e)9I04@x`wF&{5J6<4&LlP|a$Lm&I_GH@AC&UOaPZ0F2Ji)o0+DJCz3 z(QNI_JlytGe<>uC@ZQ5)XJ0Qn>uUd{&RRt;Wb6|y zNr^Ab3XY3&GfUH7c4f#$lKmw+9JiHMcT1ehp)Sc&c?>y|dkA2i1hxfWb-gF@Xczuc zU65B=!k^FkC*ACvm5-^hlES4wYXh{?X=x9G_KkKoY>xd0=3iu|M#KC^QVYm+w}|4C z5jkI`3Fr@LIG(v+I2mDd%Mk|9z*td!t2fwMUfP5H+b>E9y=JR=N<9ZRQ&CY$rSTLe zC1K&N2`l_w9%ROMWiXs?E{6GlK^|qp*5^F;-tlvg$%46owk1kidzb57&2M)U@}kbz z%WpT%oUcnkP^g`bN;GV2KHW}JS6y%P|={@W$v z2;X}UGB(vNdP<~RqbmE$cc>cBbRRO_RNQp&kTosb_^V##yhibDV{z@ajQrw=1Md+H zile#de!VRyQf$k1{JKwmpd+wbC}p6SnI77X?Ffg z=>fZ<|8K(iIAFo_6|8Oi&uKjAZ8Q-y?6t+ zF`FaIW+cNV$3M!YS~%XlAoQ-j10-Ex*<^|T#|20Sx*~M(PE(K0pxpjUTLF-Ff^<;} zhB%fJ^yffDOLQ5sY`__%e;MZBGX=0%p+3)J04e68DY^!R8vv6Z2wJk5SY2Cn}8MCaRZUIrqE z85yRI8Lhv?UI$~8Z@GJbH2l0OKad)8i<>jlxSyFT?lp(wqsubj;jdrnSjdXgw2ECZ=H@EkBp|cA?tX){JPdR^^jynyfpjEn zVq%-7on{a__?FPsWna308&+}P1M8Pn6&_%NMcgTKO$*rllUgq)&;-*SY3T!Tm#uQx-|nLx9kFckvMfs0^p08F4YJ7@T26)*2y2hsqyN*5BP z%?Gn=QCVk=u&^g(Wts0UgCrU@v|eXNzAI1K@C`<9XVLC1=7NHPwP8s2gufN@uZAjn zQ7UrglApNEU_a03C7`{myrqvHHi@r4 zH*PEQb3UBl0k}qe>St#Kd7LB#ZQC<(agcZ=-zja|6yx{+SBRHMBF+5{SlzgBSr>4` z8{B1NA}DQ@14)Uj1KN8i z^?>v5hH@K~eD&&m$}Ze062c~;>RjLpWSlG9(#Qk^@D6;=vZ{0#o0uGyFS)7fj$?Zp z_ot?xro{>2goTJ28h$e3>4ACx2*NOxAtjnERyI}uSY#$oQ=jmsv}Gca9O0Yr!Cb`< zqpyd9cAV-)85ioLM``EWhtRUhc+MOu-m~r|{Q%d~yYy`@ftf22?)0T>;bfV~dkH2$nu@6ez-0c8{6)Y^D_9XWAtF;l+m9SLhZ4Y`)8DiuM70J zMW&tOhBSqR%qo1m%AB5>7?K6`xcOy@r;(M>_{Gtw*0l7B#)}O9jnWm*oOxn&)odEf zEZ{!8_r!xfi&R*w=p&Ffa&YHz2a4O43uV?>j|aD^`%r&KOjP2&f-QIdrG?iZm$1!4U^`+09IB}VPh@TvQi8mjBxf-|o!P3JZF}=62&Hiiw8w~G+_O>Pm zmI7(OfuK?oYmD+f|)TI;Q$G#s1Qc9%K1;U2j|7HLu&2%vO!tB6=%IBZMAXuW? zPXDEGe|N*$Fcj7QsEsNhU?;YJW3f!$r|bWD&E`*yFCWvk=hw*l%MCYN=o`@Bh-d{~ z%d0oMSsyP;+cAHlBsn+64A)^7QUV!TPUuSfvyic_3?&QpcX!{qP=0#@y=;yS>%={; zo6{##Qk9_AScaLQQ5nK#NBol1j8=Q^wEcFJ)`^RAvy=cqB9K(VLZnwQe}Lpt6M5UZ zmY$T}9Z&=kYms^QPE3~+FAj#xuhf2?`x0$*;A{i~MFMCr-IMS7^9RcJjo#lu$xqE; zOX?v2gN2ds;LPv-YHP#e>+2UfPWA`)6(T5bKia^LBA_mx>i(iLk5<2EfB#12cjC4C zv+{=h{qYC?`6=9rejGA38A}3kYF*>stxM(*wj87KC^?!p`9+Xvy%iw|5R;8Ck=N|z zGl8efAI~;gK+kp4;i;HIl)J2q;7r_@nM3Rohz_NpU%miT0M%oL8l<`4n3%t?{TAA3 zxvNr7#3Ne7t5-la=+RK{V($dO^uWro)i1o(IdcII&qmbt=2BvvV$k=UfRtZ9 zP{Z~>3x0->QoIP*06ewRi*TJyl8Gw?!U*KWva|ix{dOSkvpk@`zuj&=QCW}+lgt55Ag}V`>|THsjs{#a z`Q}F66u(HTz{aw}>WkC*dYlYn_VfUPTqXxw9(uM4QowF!28{0Adx~I*R8N`v7`_7B zh7a`kqpz#2w6;Gp!7&NAm}jPUu5Y%Jnxa0`p6~1+s-8gR{E`^r!DSgw zU6$m{*?-RbBS(?x$@X(oWzuTp>(PIi3nC-eUXS)=2Gvc&p*bq6+E@8e#W|`}thZV4 z@eKGOLYx;*82e0$T@P}vfo*K;1a2lfsJU_8E#I5i%X=Epfu zC{2u~=(nP`SDpAmL*K*s-~1?ua~(VF;}pUPzw$ri;!ZzJg?2&|JWVT2uD^Ai8#l~> z1LmUeMUo_>U1O*gpbrkJkchfIO--%-c|DoSuLDk7k5mer1QJ{*DJinD1nBWXExC?g zCum*9Q`c0R_JvoP4p_eSC$5vgmu38heKPUAj^+Mu4oYI*iCrPTkxICt(APuv8jXv=UytJYwMFoMq87$VY8X&&*7JMGXOp8Ae42LnU6x=?TJQ z(*6Ez5 zkU%_%cw-@w!JDj(GinBKiZbeU?P!ITBs{jV68>&Jn1?X1rr_PX9| zE-w|TVW|)^y+{L)A`!(BDy(gd$B9f8Z1)JdrxsvOhMl%oH#gsWKTP{L1|IqN>Uk&MSM71k z?d|VN0+|i~aefevFSR);tr&Q|*!f2qAdCslB7O6pt_WR2#cah680HC_?GHJccBo-= z|2P3{aB()S=ov)P@qIAX*$=OTEL^NTeFYm4zePMAR@KZ3ly4fEN1FjZLyo^T#C0;! zBBxgKA{Q}`YLxtCzm9?gV#McVEuq7M_07)4hk*Vm%$6)r6Qd~rq+H`&GqtN2lHkJ~ z%ZE(|&OZQ>2hilihJ$Kkf1`r*x3gzv;cA|ZF=^*rF&HC3J`CHUmH3Sw9+N>Uf9bgB zpHfiwmoyRK^NW=48YRaE7&5L>h9+DX@LtiwkbLa7_qJ93a*`1bG;hba#T2of>VFz( z)RoSw`G}`bD;_rOI5}*N4hvACTVfwuV*Fb*gIV2HcKDCeX_+q@8np%)9Q))D0P%`2*yXsj^ zXv*Maxi8!hn?Y6^2khNFBkSW;Q){Y|n;)MT^XJbI7RJDfyQPEiG)10xi^!p}JbF#n z#3GBd{&2FqSu~-B!n}ItUEsn%hHdbFSTA?;VaZ=xM#xSaNpuQ8Ak|AZls}u z=bdG62{tDbJzxITB*6|1NoN2AiDk6#8fQEwxKHHtS|=_VP*T!5)8o;eS(fz-Fl86M znv^t2%{17rU~r?47}&|*j{0eC1B&vp!fi~Rk~R; zruM2tNBdJ&)=2`*OWn_0kB*PImj&vZ%YJyeJd&o3O2-G{{R1Yl_Dbvt*}RjZDzIiP z|5#?WJixT#`0&~IRXEuXsU~8J1N7j%S!t&S?ME-^`zIJMj6N&t?Bc`J=83BSL!H6-G{te+H0@erbpDA2Kww+aqydt_yG z@c^=%xmPdktxF3{g~O#&w;p?Chn?PjA{Gr3nz5soN#%}qo5 z=ZKll8nb&3=>EVoy|h7am8+;|b$~sOz}ySNAbN)Q|G4n!v^BqA1%t=>IRhZ0&2<6Q z;tKbhXJ4~(i(_bA9zSZfm9TPD5B&TMN*q=&GC-UJ$rvXN`vO6cIcV=~edUBEjVy*x z?L~T1qG621KtiGv5YWan`YpFlp#;kt4!H)G?vNdlevMA`Q<|o_DJy~acK(2giP#@7iGIPI$0<7fhY3M>ahQPE%O{{7d}#x4}^03bkjMQugh?2v~yG#j?r z-#Z|R1U};~K$<=DmlT(^LdLM3U14Hbwxg21?_gRAmH{iTONm|{y;Op*VTJ~#_f(^H zMm+MhxA)n|&~vBoebt@WY+!9In!W#lHn{1~Ka|ydh$tb!7I;o0-%=e*shUj-zgVX% zc60y7`BFq$tSe*cev;oZel84Oi4bNfktw`5UjeYpi8(a`TxDi2P0hR@1<_-S%w_VI z;2T-R@#7>Uut^6DPijW+!Kc>b0NgV$5RFq1;aHS{gqN?G1EF4EW=+a9KGI!E9jreN zD`6r6P~<9}!KxKF{sK}FXhG&ICa#`6J) zH^u^_R$>p2KbT}Cm#RW{0QurNAIdH8yNRaJ|GLjZU139WYd3A{@bWx3K{^;4H0(%H zmT{)}v(RKeUcD=j54^v?%u0h0@vfIT`+vUO5O{?ydkJ3_141Bd7l@kbWQb117bR<8 zNHUk#dg1{f{75!DFgWV@KvT0v#qFHJozncVQ*~rm^Sa=4HWo5zL;%X|f!Sd2TR^63 zbZ4*^Ufa{qXx&z)d4(n?C((;fV`4OFReiT>-ATZ2jS*(iV|OW5UeglC z%DwUYG&0gb28FtSOv;_0lS;6iT1E^1%~T@}J+PnWmIL_;H2;MT>YE%9grh>r@`>rM zKyvacgagI5Ttd=N>;bMRK+tdBvJnVElWuoYChij15B4$At|eBYAjcXLA-CEX_}{lRkR%>(N^}8FHYv6A)P%XqYIYJvj-} zGA)AT1PJUs-|pPeTN`02eC7Ez^{lh7p|kVD zkYk?J6IIu%9J=kR6rcT%cTae&*H=ZmMjJ*e&38fuo7lGwHWwWQ2;CrSGGYek1^S%y z9D#32>2U2NUFqukf8yfSO*{y|O5m$Jb@1|pP25VZ#RoUXwJU3MhEt=>Qs0!KWpkM}Yu?CR1Ok%Tx!NekR0i0!<*!R<-+|ruH~s$W?+rp@7Xq;5=Z?dZN5!*U&97!#5)MP?Sw2?-N#^L_kwy!f{`znR{-09u zQAj%ds~3SLRCSe=k2ZaOh6F^0_b+(^(+xRLBr1D>uk{Tl5kzR>_um`V-qmf)xQ_DD z*4%=A=ySebBZ0SYUw1}Yl>sgSvrD^zk%bs8d#|}%QI8jQT}w^2!0Q|TuUspvmPlc* ziEC-?YP$a9-Y z<{Llsu|d5fZAWGCM->ZpT}xV*q4$iISIQo?Y22kWG?H)wD+WWbZ;qhY-hQ;{n1jg4 zBn3fCWaRY4fki9(YwWQzMh|5(5K@xQePFE^!F|xDcm@}!A?5$&ijH9I|CeC-dbUEy-U&prc~$wK#umboiBJy zckF~WmYzOBi7AmjW5f>@YzPHhGmVz;aeb*ZCBP8ysd9u8+)WBRn}#L!Zzf)x3DX_x zImXBWhX95)&vILO=sjlX;fKVlFtS9xtLKH%R7#~7oWq>ao`d`R*lWh-8E-abgW)6D z7gfDIsa~#K;D&KC`@L0DLEFlWTH5o?_-#D@-yv?&)ar-p2-(FFZf_n9ScvT zeubDp>g%sb!Ji5Q-okWvymLu!Z&^g@(PV`*j^HfZn^vztbtQr|lLr($U{?fOH6`u~ zmOMC~<1jJl0)9Xd(H`Za0+n)h!us zC)a3?KhumL3_5P(8Irzpx`XtSjBB>uOKn*b^VBpIG&?v*Z}$9eH1_#(Bov#TM$42@ z(ZuHFE+vFbQIqReGRzDiWdT)LlnINj1^mNjqlNjK0QM3}8<2~NcsHcMM7ASJ2vMpJ zcA`C(6<~llJnSuO$nZdV)X|+H=A7r!!C+}XT|IvkskEKY95>G3X6A{90G%Y4mBAAl zHQpv6ArS~KNn}!Ao+#xyXn<6%sexz9D0aEGUH0HU57S*kqayI-aw?^=MdGqXt$}ej zEHh-Ec!c6#+53!(DAe%a=vg#sif7h`E@-lj6P}I@`pc0lQXW)suA0+L6bt^%4FW4C z@R}w@Uj;;|g!9hP+?}kUWfW?{5RyLEam&(uv4(yX_%$6-<<4J6M;}hMsGPhTuBNPq zcTvOiddz@Husu*btV7H!UxvNlsWvtT07rB)#qGw;TSMw9>3IUuhbDQ8j4Z5|{lOgR zzIOFzC(D~$#Tgen9<#{O3d0`?AJ+>2F5xCNUL3^#E3*fhlCVRQ2Ih~z}=WOE%EqwUA7mO!Q z{*$B}Z#|2&@N%tM`pQvd!~?Yf85%jljmq;bLy9oxM?!)ccK-7$7~OleWIdupSb|Zi(4GOU}`j4$S!yM#L2lF zxF^v#Bl+uzB$&pZhJbzTT5vd-)%<|B;?rvn>+A1tok3_1<09^RI}gAR<} z@A%^j>%-mU&7IuiBH5MR0dGG2&P}IS`_mxJOX#OhUFopq#|exIhgV=a!l~&O3@zNc zONnKmC)zziDFBR^o5OGW?l{hDl*WWo*cBvkN{P_vtn_Y)5Hjg`04x%-9l;$bsL4fN z%@SD9ot>Pm0^qAyRWQFNM*+hkWT3cQW@_p>OyoBmzSkCDQ~vGbvg6*vdGC;Y+;up&ner#SiCWudZ6Sdeo7UP1m)5GKKf9BYB|Op79qB33 zVxIQXe;>%LUA`~wIc?1Cx&30(H^@a(=_HZvLOc@Jl9G%-%nbI#d*LJ2+l)qjC+{vN zE!Fo9+&?&27QRm!Hoi3eM77Y~KU{=}hzLU~(6rnL4&K#Gi_Y@C9$&AR$EkU=%pi?T zd+E7vQ8}YUYxp$n{QUYO`pu*WWtX{h2{BZT3!AAzh#C7_zrFMF3fiG;x=#(sU|yZI zv-9IDKAsfs=a<>wZ!|GIU^WnSt5X~#LFIFQ1Ew0wX>e1SsHOGUg|qn6rBp;jZP#90 zD`b~H(~0&%{BI*Hq%YVmm*RoyS4%DpO>aJ4U(hBTo5m423uL z_O@3?N1eg|A6x0J+IB#7t%=`iWWZuO89t=1k6Re&m%teQ3WZD}md+z022HsMUQYtY zlNa$8b&~%&4b5HOnrPNgXW$=|V@yI+J}kL8PBivcld)r*-7FY(&Yi1l^1OcCuP!nP zogq0+4%AH6@C-+#;q9m@tP{!mAq=|5i)THilKa2i2zdctga4#} zYGF193$gUz*t1K`N!`I_LRHx)VlkBnqK?O)CRtYYfE>IB!p9t@8Ng8Vu|arqD{|Ail%e4IHaqYq3wlSKhzPHuufHmR13FV@ z7xTtt?%ko)BKKSRV~Iu@Ks{XFsMds5!E*1-dI$^S&hdu}HNj(TA_d|&Vj`kf#-wL3 ztfz6;L(}nhqqa|g9Nfy%!-)GATHe~Aj2!L|m~G|r+?6X}ld=6kS#pg_%39*#XO-E7 zTkvXn6}*V*=|@8A8@w*c^NWeo(>-jZf>|t={~X6f$Ji@c^q9)_j#@f)9=gEuP7aWM z?TGOdR!=$x5(MTEoN8!#!i-44pt*x-iAaI^S$x-vN?~H@SL-z&YqGLxSVQ1w{90ch zk_>Eix*k3C2Yn7h4IfUUhjS)oc==K}Zx6%QqTD90UD$1PR&pCe z?vDGB;p4?|SOgcB;lrLui{-KQ+X`n1N4l+TN^4M~vs3*TdRFKuvkU>=aovBk$Ab75fe6vp%(KH|E)Z>O`6GHF7- zy#I3&^q)T)GD@Lru)0rCG7~<}&ajqa%)Sz1X;?Go=D2AHgA|?O&k{JSmRd0@p4&NY zceopUD3=7m$WGx_Xu9g9Pg6{e7!r+GYMgmjGg&{Py292bgMk$8e9nqF>3=?Aa4g+w zv9}>FJQszu%QLSn@@Z)3i8(hcTy@XuD2CWs-5*j=pI+&y%6a*GXXiM)frctPu#vGz znF{AIG&8;53TpPbDV5I&rN+V&IP4%LVRI4jlOr`Ti^*UfI!b;Hir4t4hu)Trf4*@V zy&{)ZubobnlftQgCkBbjY=i;fpjPrCSZ;;_re5*x$1p(f?!O*aR&d`Ti2qp-O}ER9 zJH#lVwV0s;gSUfw_jkOeCk-;p>;6T`_qd3Fp|;!6?cd%S`htdUW-@m5NzshVVy*W^omLJC84=7z1IzRZA036?a~c2k zw#R#LYGzKFh-mG@GG%D1`skzE9B?$=5rdm&<|2S>3e_GhMELd>^2{;wi{=N*G34-v zi5N+mqG$6Uq&ycMUgV3*&R!wIuZ<)4rm!kd@r-_{#$hMC?G z%u-Y|QGh~Xg40J)W1L<1%y4{&$*7~F`dzi6q61d^SVX^zmzVKzzd(h$eQqVlphRIU zD<0Y;=+fl%uUDgt$cPf2gUaZ~^?t<6F?6^a<{1?$w8cUQpFf?_!bN0PY&P9S74|D; zMg-w0PiY`+p3m*N35JGlnAa2|cWs`sMEj9$t)0Pmav9Fg^9WNYuhC)Z)->|+HFgMl z*euE0YiL}xh5(tSEWikEadVc+cJUee&(Oy<73lZnORY0#8|3M9vI zWDQllBdOLI1Ir@aT_db+r)WUl(EhWTh>nm9fBw8yIE`DK+&Hr|b+LO`A2Pg8oLW5W zWCX(Dg>=3s1N(B;OWWXaK$-I*b&mPHVfr$%uSk0r?bUTn%OlViDwv6m|5NRGd7eq`2<@L7FhFz4_o`b4zm zz{dK}Kmn>a>$8RDfLy?F612deW3|hwPlrR-kmP8vnd)QLm%hCJx8|xbs!#z48W?Fx zeNQgWfenL5P2Gz%7TydVi{pZ5Cf@eu!A+x4ugIL2RfkKdX^vX($V#g#E_XCP{diU3 z?R=?)q5IF)K+!WN=RbppYHPROeF=$tQ}dpO5`%bY*zL*v=MOyox++{N^xHeG6jzWR zKTs0ujCodezIC#I7xGM|S(n#Xg?aofg&(@u$O1#9_J6`>rOY(f~#L`V%hVoy& zWp|R%>twXKDN-H3h)$GiRgPtH$&bVg3zOG$H>n<4Y`>eIgSC8N)4 z_k`d|nrQh^C*$|%i{F`rmEMZyk?ZIZ^P9F-gvPc!j>V2_Y z@=3pr0ei1~81tZJ#|g4^d%;xa>#J4f(tura&VHnzK`S|$GGSyr-dj*B9Bwb%OXWt) zNLUz{Soq%})Fn=yM*HwPKI_dIHOQAIQv(`aq7P8o5hnt zuu^h#zGEzMqq4!=Z+A2+Ht^=z(>RyM)YN)GO??AZ)2id+J&gh1Y5%%lJZF^l#mjgo zab(!4-X7~^*79<8pF6HlpvZmyZMbrrp?LjZQ?qHOK;fj*Ao45}4@#7t=gB=8G5)_f zShF_%D876)PC}%s8(5r6YpSH(cEGJ#doX30IiqL^#YIy$HRH$&`6{(N{Ie)yGD4Z# zDhUiAn~BGs!w5cKHk*fV((6!eGur+;_2hU?x>?_D({mtq(@72HLQo`B8Nd!(pEyXn zX~fsC*^sj6VfCK=>)qESSv+;eMQ(+TO?T?4gttT(2owZ^bMn6zcv+7YxBmP4#_ShXS1)-YqO9z^)`^JzcMy-^v%6_S zn*37mMs9J~W>n1K&cE`U@Z93Iqh^qA*jb7o-ymNSD)KLd(-KD~Q~anCNT`w^#$Hd$ zqz%;F>2S#8d!ZKexS^pcni_Nyw?<8%PJBw`f7qs?toIL-b%zrYjiI2s#h%kquzND2Ab zypFdyw)=fjV(U!v3oGKwZBx@2!ny6@`7mI~%gcbDIiqGGnBIB@JX)GQ3-( zG~aoN;5WbqbcHwvdt5|)j{ql;7-$UX%+UZcGWMZYMWAL3z<5gcv zMG-S`!JhxU2t1m)U#IiJ%guVehPaGkI$<}F(j3(htbTr;`oYTc=cMqa8PwOAAbYPd z!!4c``6W7K+VfWeTCWw>Hjl=fd*O42{rU6fh7;rZ{&fw$41~wwakS-j@MZ=-_lv$y z%zwc13848-JmrD0+t6rW<1w_3f&l0M#?hLAFKCZ*N!cd`A62pHr--r8kn9B(i%a-E zI1fn5v|m@})KY7ft~ky-pwbmIH*yM&+??{uzU{7$td&z{BC!Sn-@VDUh z=~5E|yQW=-7wUIg*8e4`OLFPYg5mDC_3>pN}gX8hn3dt8rTQXD5 z%uZdTeJ}_W+O>Q_J8p`g)r2QI3?3`6u(NRwMtd(--s_6`S1vLrM$fk5p%EWOB*hY5 zUR*Iqnodggg0K+2>FB5Xy27Eo`dG;E?pkKnH3(E~hF3$G?)hoo2sqpoZvNZ2xjlN@ zaw0VtGRFFPFBFUP#Q{|nnQj>9JAKE}D-*Kr6&2;F7P^f?-Qxe<&dLhA)oTO*K`7x7 zbl?07le<0si*JqNfO#~q&BMAQxRG0^oK@}=vBO_PNQ$n8l zG4Un3wP`s!9y;_7u&m}iS;6VM2bPAgzjp?zUFPG0S%focd+uuEwL<1Xl$+m3RT7*gE44<|LJek&tS@>Svu3^NX1cKT zMQWj&UF;?w@10l@jSTVv-V`B7 zAAA9Df0jZK1GvSpabY5&*9i+@AMly3?IH*te1zBjU#ubrbi>d$MQcHwZ@dkCr6Thi zf@`9y|K5G}mwlb{vVMIB>6xgQU^d+mJ;+*m*Q3`5gMf*(l`sLI1tzy*ar3w0$rl!z_HOvfd9A(sin1{q^ zA4k5sEgLv=XJ5`WuXEX5C>L1z4QT;(&3zl2Dib=7&@rE;3t+fJ_$*n-TcKvBNzhBy ztyx)P@-1WO>xT#DCk^1B61_@3%2fEwjP{Ghp<_FL^}M}@#c}84?)X-QMBVakvWaCJ zYgS%)NKf?h*98Qhy8HdmjLSebTjaLpL?Q+Us^+F&ushClNnk6(%#_?Z$vz?xNkVaw zGO6!)-Msn+dj{F8_;s z{BoNdmwp6~fhTjyVt&ED^~YloB_8B>6B8k}q*nElP3*qS#cJFHWP^z4^Mzh=EcDLP zZwUfN@~lGoC&pIo0Rr9OrzCJimhLtb)byBV3!CFZ$ty^xf;3((2ZPz~xObA*uQ1s1 zPnLT}olE%cI!+SsJB6T@No`+fYwb>BsQv2m6Y$38d^(X{k&eDIh2z!U0^!u5D` z2i$a2^?S`zF{y5b@a#l*!zyARmxs!~xc@EJm4W#)2>Ax-3c_6=vN#tDSSb~k-pDW1 zx}UUqmw;nI1G!`;k~br#>Njtiwb^iS)!EC^^5c6WomjGm`^J!w3N91}r_aa~Ib$@v zI@l-g7@3%qZQ_eev)~e-de=5+Z#7s)HIB}zz!HN|Fb$fTx`#nW?c#&mR&}IAh(16# zU58FR*bkHhWa+3)Z5Ixk`nOYA2WZmmr)2_2m)b^_?X~)aR9Myt6_5icckqzwz&LxN| zUOadC)DV)G=y>H#8uab6C4y552%m-I0Cp>=)ZjnHYFh#t#8$!fF>ArNtA-pK){-1c zjvX;EwM-(rdiE@p&+8$H!69@|nRVuS70v<9ByM6=fTDLe>HPQqoWs=pqMGeK(AsI{ z%PcPLSJXTOnyYH{H-UukWUpDXF+7rbH#FV9n^F(*(1-~&Cm%$>or(quo)r3l33t=M z-y;LlHqH6miz6yW%PzvjwedmVz5C))`NF~e!$o?cU|naYGO~%RtV%^{8$y}q+}3TN z1ZIq~bZccvQ}&017YW{rxVGrO_{-WamX)m|z(1WagdEF6`QCGeO3K2ZEI9pUut>qO zZ|r)p56|8Wp=E;zA1V;rs%ZY3NS{%)8&bq;vT!w=s zI_6F}!lv~E=(n)3@6-EWS97J}hK!>$RQ%{M$+;3ifOU%9I%kZCh%^kvoqpEjdu!-@LA; zz+3z|J6knMfAISwS(+r&+57>H5;*lLkFBI2fq=gSJ=KkN)twzfA$De=zzi>PxaYMs z5%7_&KyQtZxHZjYM8NkDgPh>F5o+e{-m{wDgI4Nl;M+ZkTO6@-FMh&YFLs2*Y>8dw z-ybPaFYz;2*=0XNDF-acuzof^tQ7%YjCVmPL=j83en0S}gSPQGyMNSbKH&{?sp4ZU zUFWnU#@5O>e-}^-H8WEx{z`*ROzim(+M^SwS7Q?~a}ad9Sx|SU=OpBzqG}DW>k&?f zjBGDgoIHk>mw!%DQ1rKHKI$0QAKqi~GNX69`|Z0nnhB$c)t>k6$k8d;Hvi0e`rYPQ z>e*dS(=;+LyJDoMbWU=886f%j-2Tr5n60QGnV%hO9#*+mZjSQ>{7Ew$W#AH~R$%OI$K|Bgc_QNtO;XN>xDdfPSU1NXxO$ZS|4t7U~Edu3-FviB%SB{^kfOH{_O9h(N(DSm#~MOT-QRtm`Y@ku8*=0ZxACw7nYHSr6wj$;k&Q>}jvgW^;_PG`x+;^I9vQq_&M#djU94&1uanO^6G( zt?1#mx^Q%LNAY;qP1J6lbU!`FCuMz2<@1YHiXKr+{;Fr*9g zr?vM&sPzSr>6rt70|=Y*9HS71Hnu$xhtpAh4o9AMKla+%=O3_#=4F6AV8PWUjnWLS zPUg_iWL1b2d6Pr6{SA5VnjkAgFTx3gkiN!G?;Z0<>?v_x_SKP4Ji1W3?#}7kx4VhS zX=xW*=-7O7_rtOF95@S+;=7DvdY5Dec7Y5s%e|F}S@CTQ4X`4dRx$)d#_g$H8+pdF zOZFE5mZ@cfmd;G8_i5rn=IT!ze<-mAc2uRo#-dc@T+#K7`4H?){@4E0{-<)LB)9gQ z1dU9jY!e0Q4u4W>fo4X6gf$_XYGiCYGUSpjIm0ckW_XDl5>(3R);&gbBjRkD*;K`c zUTNu17Po{$=K-4fetX$$#@cnEOJCg76ZLHR-kM1R^a{~_a^-rAy2$EMx6bff|Kx1* zo{`RxpM9dO;YI=$PJ%{CaJey-IL18_!<)wmXIjCU(t%l+UEeJ}Hea|EP0$z|7?=}a z)10DpNZ1}YL$S5hK&O3Xyd8%2Q*xno`uCA+_F5$T{G2lsTYHQtv zx>E%=m2WSp@SOzF3tVO8w3eN38@FmACO+$5yX17S=BK3Po-4-7Rr`?APQ6+ZJymEZ zj@DXQdB1Jrl!~ua)3(Uq$;NH+mk(hk9%q~CN%Ma;8&8ICy7a0S5>6k`v7V#4fZK3#Qo6I!>PyclLVLUIpLE;O zt^@8LYGK+sXP$`h0KE|uV8B4Q=t;~ zdXJ0a9pleJ)QMQLofSL$yX&c}uD=t}2_D>Uhaa+T@3MueFE#4C>~rPgVQPr`FMTj? zc7ev+7nuRShqb0vR*rf1^y5lRbW&66a;+8@?WMZ2WzsSl75)3FgYbCOBBqhp!Sz#< zAv@4pxHKip>s)1v5(EO0eba__PO&Px7UskKMj`2$5lqZb*|M^-$-%wdSz6+fAAVZt<{X5%4e4Ois zAs47<2rS|ZjX5u0b~{opVI>&y{QAH<%p64dC8^HQ!u2q6a9`qfN9>=EZ(wJO%mNVO zR6pk-$bL8W1@iQN1Bk8 z!Y6FiC1jM4KE&AKS1VS_pMWb`tgJ5Pf!|c#6W3YsVj=Sn z^YZed>@qEj+ zsXS6gjIgDplOSe!Nu7gJoyW2wQ&}-DkBK?YWICFfUeF$RaC(lYEpa(1r75PX%;M!Mjp=$G$5kB-^>bK5!}pIU zh?N%3ib2LCQe;T+heFMuEN?V^wQyiSK}c95Ey>unqj%|;=Di2zA9P5hygGm1;NUdv zLgk?T{)$1_^6mb8>If2iFDNLeH`lBojZkRQlO!W@Ub49^lyfOcY`zd z)vKu$f?e0zTG3qj>Hus7*dS@pbBxm3wi0&4Jx$F>lHqRYyX)OGk{T1&Q43a!YefU6 zCuvMf#FhtlJa28fnE(RNku?=Wq4#2CBg3yuC=g|WEpp5 z$T{lz8Z1rX54Tg?v{LJJ!D5bMRHr1%wpe!7hFijysJy4td{gV|?=w7od{1+grQdaM zRp{zgT*k^G{P|tp6)I=ve(blv3%i}1YDEl!P)C`vuA{#Cb)C77<&1ZG^z^Ag<~PZ% z*S>4t2HQUCevS*aXqnP~ zQ{l8j@+e7HB$0H_k#O7dtWxiZ-WTSJohu#I#g>v7v2AK9$+s4iD zif@$Ty-KI1;@gM54K_|LqV~cKHrKy><9lP<#VI-O+dkmKff>HyYU|Ih=T-=&b*F9U zo4%!#kHbROa<|E)Q<7UL>V-Q~RZpy*K3xhZT74=d=6Gvxy-sDRyogX*;$wL17^l

?q(2Jt=T0cAkpE~WR_$2wNENrj*^v}|8 zUS@%xuTw8vT}DSP3Bxf?Xzj#amk*g<+3<)fBT7oReHn}`;0MWX3OpE&Afp~cJGzEV;fmJ1q#E% zjtl2QX^;I~^OVuHgv=k}19wvoob)#Je^;7A5i&W2^{gPimHQQ^QzC5LQVKQr* zo5XWbvt+rGo0d*?>G!vFOKRzCH@;nW9+VxV*h>jNXP2=Zvx<`t=aJfRcXH8~ zX7sg}XI+D^qbrjj})+R_TB z&Wrws{w(h7Nt%@^9xii&=Uu-8TI??_DcB@A|F< zuCKdNNW0{^pPHHtUzttsczxEh5yjd@$MsOjp){FY+RB2a`0ZxdvDqGH3?JMs$~x)iRR>C!_Y z2P;N~M=4tl_*5N@fB z5$4L@*}>spa~w;t->SMUL_{{Kxico0avbi!- zVg12mT7#ghq@Jbk5^^i$-D!0y(%^Ee{$9{4=ZT*(leLEd zWDl8e_4%j)J<>|N-WkGhX2RqY71al}^-+gj-ZlvA`_vp26`f&79S7~Bz2l#&*VwlUk)LP|MM%&M1L{(^-_4@fIH+zE;j< z6C}u!U-tmz=dmaU630jv-FT1FU-#~6Sjs02Uvpl+qtA!#o3Qta5!TK<{Xk6(*I#t^ zjniCTn$*()8Ur@(?L~ZKC2zmGg>C%sj5ZfT!<^Gzzh6TJJAKnehk%&0;$qh4)YCVU z12B}8l$Pj{qm$FR3{O!ZrYMFIScfhR5e;9i00)n7v^e9@qtQd_3V>kX(5i+BA(Vsy zMPQ6C6S*nhA*oL3z%sx0Mq5HB__uV<1TR&@8Yw48Vh2h6gW>F?$%O4xNGg4X7f5!c zv%)vu-z9b0ks@BPN@d#lZW7>P>Vfx#WutuiY9O4yv+^`>mi}If?8YF3o4K<&COxbz zwQ`9R#hDPeq5Kv`8N6z0BJH4vQ?Qo3{|thwV?#}^NU$LDbjaa3|K7#RQ1A7k8etdz z9zIxeflww|h|szCcXHCW7Z1sv-debz=u7It4}HTAlJtLXx>l}SG`zBx?MisK@EUim zpPouc*!_noc6@v*I{AmB3i4B`qop-jGGwKj`)9uXDt_Y-hb!n9u;DkzcgMAU%J=cc zdjn^UorYy)W#dXVaJ~kf*yU~qWXdje`OJ0+3JZUr^ZD)1bo}^_4oyQWHH(|Hxa(XP zJMDo36Zwi~6ne9b{9#|&P0ZT)mS&dDiNOr@drV_Df-2X7u91L2u(xo?NO8@=qn`8&T^ZTb)l z7L~ZfzELr4_V5R8{b23Q_be0@dVrxnDS*-%vk1eW>#+D72CjuHA-T{f!bLw{W(lOt zYXGmY($Y4p53wyRX$_lw(Cb7uP2O1z95RA*e%tkhpB^yt^knp|&226G&OS%zC4|n| zSt*G54n+StGJgs~C}_ZaR5lAgazGz&SlddHOTW+N>^|R>o)#aMCN%ZIlUf21@PTf} znf7yFTz=nQp>;4ZanTS@q=E+Vv&J+?;eWK=x@sz3B0!Wy3i3FH2Ajh>HBz{Mqe%7# zM`N-#zpg@H!xF=DPnzG-A2fe10j|QK`oENvdbau1zbh$eUrg@4aR%S-s@NjQLz>D` zP?3zf>^KzDaPG44G2{ckK%LN-0kf&H!?oyLbcZnU;Ei8w`X}a71zpaJZ`&4{cvi!C zuvp<}4_oE5)cGR+{F4|$&e_TBjZJh+hRmGdPDjlnAXBYGSwLCO>ndB$k6?r~AG^_AW}_uaNAy|$flfp(<`Su4~K zT)QqRAVmRPR8vdDcCbeBfC_9rW=Wp3j9GD*v=ZoI(|ieh=N7N;om3T@{XbV4o~b8p zAxzhk`CTdHo&tk`GzHkG#GK1EV?c0;k*}UQ-!<{6ynTG5pfN7f`B9lr-z7R)ZEN`# zf{Os!mhVD(8W|?+IUH(b^`>I+)TDZrf_=>h!V9=#``8BKId)?5Ye3`bkR&aYpfU7* zOT#L;e}M%!hfTFa`|EX6I;g(b@S%fb7eQYN`^W6n&my0aXjTl+>;53UMVuLtoqgejE|Iuv>8afGD-I-z!zjOtLAQdkWRw?j4jmZ}O$ZxUyEWP6tG}^U z<1fXJj9R+r&!{K7FH1%OY%qETI+=ePm5LYF+>*(rq<%~b*cWfe_?|l~z?Oq*R+~u{ zYpJV6MTk<&Oxb9(A4snGUINfrY+S78_%TGH%Q8KkFBSe;o|c+m#DN3dgfPw0)P}C* z6?2!e$up3@ON(l2W!p{2ywoZu=eQB;l0aqnc29b+x3uJV)_&CIdY-BAar6OcEv2vQYvIGsn8y85bd2MEE%?9UXDf&94=gRZ&mnp8d$5by=lS8DQ!3Wh_ap7%uAH77WUb8v_+E#Haik@_0R5KI!PdS; zMcUR<-lIl5d9~6Ip)^A;{+oZ?*(8mpG(S^8P`kOsu+Qgb>Vr`Kv*db9Qo7wOw$E?j zu&H$B#~Kbzv-IK~li9oi=ViM6Cy~2NIEJFcf?Z2TCQH+_PFTKBK) z?eG7xXXJ=*?fS_aG2w^=zu0_SJO2<|^*8Gc2zTKALuO8sWfNOM9Y-~y98hOYsjn=JGd_pPBq)^;y-%i#|^ zynOQ4uLl6L=g5;aZtj^NQK0jjx^kcJF@C?f@9;2!U2uFtSVqkfbA(8^1wiKo)R4kF z;#L+!$FRECZNBICpl+csK_>M+MyOH1+gFYccyLsrT?Z(cv(LCx;5IS4b`?`MJvh z8BGnaxyv=zE(w}4&W`2F*qTY(ntzX$k=W(H|0K?u3u?<{wl4sn*)yUV*4Tfx_e#)N=bunf}5dIf`*7Xxo6DMBTQ!Lb$g}g zo>xdeui3f&o>|%4hq_-iZ~*nsvoPx_|9~1xpQi%wf(#fh8;;$|nCpJ+B*mXS$I0e8 z_A*$mMF^==goO?b-KT`EBP(^IYx7I2rP=orrgn+3FhXe}v9Fk(YIv9dWBnkTC;J<( zB-`qHR-}q?&(Q9@`YQ24-`~N05qcCL1pHmI(@+yFv{bWY8sQJta+bjuv*vKiQy<(- zkBLbrG&~IAgR-K;hft`VvlZXNRCOmag2DP;>BG}=)N>~%e`i}rH^0~7w|LByGbI9i z0Q0OadEMzpPI5y%}jjhQd@ev+B1+NT^(iDJV_8eP0}cpGYW zQvs16O^7VN-AfMGb=k?&d4F_|kpUGo_NK%$>FXTP(F^SW_+sHT-ndiC?#MMAgx_M8aKu15{EF9l?xdsYR zMwe1p3r+pbDBbi_eeCW`*kClVH!@su0tOZ2~nHw8;sZJ+^SeU3+Wn9dh!xWUV zgYKXWr32MiCOgfPKh)lBnc_t*ZM*`R=;FkA7q5TKLn4cb= zsyNRgB_-v4eC@ek{Ch?eQh_o)z_Dt^j6p&oq<#G}h@Eae1b zJ|u|XozT@j(U_C`23UM;pQRCw8)<)UFPS7DBj&0c9Y1%dnf1G)sL``Waw5O8?Q$q}rFOji zCZO*!EhGnDPRVjFFRzqDWr0=i3^;)(2gfvKizE!T8|$ zDVvM1-2#%X5ugadxXcEUi4>}0$8iOdvNXq^etYhXjSCFcR6QZ}79XcOFGWk+vj;>n zSY}hw#?M!&#XV=87{HB)EDJsJ>%*b9=OCs9Ly+N<_-J&BPL4 z-_Fuq5L_NLLAVj{q_Wf07N2`q87x$MC|E&20AC$sFSWNsra4%vJnThGGzx2AT)R9 z82bKwffZt#rc9aUa@LRZNbi0hy-b8wnW%Sww&!Eki<4y})~gTHZ8??Kd~Zvi)hI0? z#}j^LN=gy>k^hDuD`?ep|M`>C(3`N=rRkEeaBp7;xcsT<3t6j?I{tmfG`j~mWBz!U zdXW1u@JRbZ)1`t(ZXm*1jqs{-shWZefkXuq4;w;P{pZF~&GJaHG#YAl{W z;(oN9-B`;cH9}siul}8#Z>DIw(%*d^J;;Abe2lnFL*ufp0ZIo>gw9W{XpEv zSxCEvB$e=_eDxkw3KM{gDOSeJ%qPV193w`t+o90i5fnkR%o?PeFs2c9=DcXM|4DFV zSIy{QujHUJ5gS;l6Zc4+6IOA9v>9 z7gF=ueEs{n-+J#l@SuttAd)gW8h$+!Ht{P-=qvV3vP|Y3iehlC)^Q0f zGxH?UijUrqz-xx*T0vx1t@K3)Q4l*`O7~$N(Ys&=TLm#G*-VJLLWU5Q@eX}I@izsm zM#GnLHc(T4@w0iG6ZpI@XdUS3qk`9isv%ws%d=q~!P!N2X3?#@)vHB23C>Xi{kG4W z<}gNgeQT2G_-{}|T3UkvMxl0}iv+^CHO6zp($bt`*}Gq)mzR0O+&o$BV=`$ouNPv- zb2V`npWRR(?k5jJdVRkqLg9D|lCaMdlU2{}$D4YT@It^G6|7zEb~idM1q{39BvRo{ zfx@`tx;!9DTx$q}rxvX=QJC3$(5=5jDD^7iokj69!Si!V=np0u0{bA>A^S#|w=sDQ zDGvQ0&>JDrRBYY|H1TYwm#OKoTWFB-AvG#1us6x z1zxps)$_QG#v?L$tN(qb{pZmpj_W`4(gfK%gWH z*MQto$@?mVxrX@84l`Y3vt*1ZAHN7BYIyD_SXuGzWnd-q>>}s(t?SA4BDzCOpVH-} z+e%9Er7rTh`pPPi2L6Z)$I}&bkc@YL_ZY^x>TyK^y$20ljwM#Q7o=Jwt)=X&Lk)iK zn!L{X#$fFlFarwC6zVkIX@KIFvZ_q{Iho6H8$>oBHVa zx?5yRaPg180^Mtx;PUE}qW9qI!<$aWo|`U*>FckY7K!u)D(s89XsrIM9K!N}@mobl zcT)WT;j6j%*EY8CuZ-z4gLaU_)Jwv~_b$E+bY5HT0x+73sri{QuYlg|?m$r-S>EU& zF*asXzEm=uY`A`mrn>y+9)|k*$SEt`bfx2f$$aA`{(2dFjyIwKD1tN$=9i6~jlQr% z0=)+RCSatO(B^9(MaDD^B9qNo2MI>#hlJrehq5$N!9+b{qgM(&@Eu!sr>fu)Ywdlm;c2x@B-m7x~QcB0gVAuN~~C71+IKz8IbIO>I;Qq zyzYRpQIU040R#S;mF>#jT2jc)>xV2e6Az3Kx>UKD86FX*U^An3BZh`dfimR>?wCJy zN|ra@GU?W>U7``0{0P$ZGbQye#|Dr*CL^W~etK$cy{H6s#gj9G2|bNJ+}hgkPify| zNT_gwWZWV?$K^9XMk} z3=KD0CN<+ZJ9eS`9v^3V!^Di0x)LcSo&pqI7vXghD3*8;cmJ7SZE&`HYcxO-Vgh&` zAA@w+x+tjn$kxTSsCPWo#%3Kzv(o1u_9 zdmnTS3@jzIT_9&A{zF53g*Eb>u!qAoXnasWpWvAB@7X44&r*TWUTzIhAiBxE3n9lf ze)rGqhhfW2cLuz_iA|M{jtPZkRKLGbQfJ8U8+kN;?9sL~GE(x_+HyFZW&bIRBV|4Q(nU7tD&ngnb|i;E6d3}W__uHP2)<(9_-17Si&XrU55-F) zo8$XqBjHQ$NFE8kc)_x+5BE619l)MY!?MDx19Zokop2f{ao%bu`?i-lLo?vZf0rlZq84j%G6oLvu~WUggtZJj{u1m3v@Fp(96&4p07&+q?n0YHw` z{kEfq`VfYIn{^1fimWR zhsIokW^c`ofbY0Yd$qkazHk z!&Q?`K{;SeZ*(OM6hq(}15G9JN;)uiGI}ow)`5j+a|E4k|BDZP6$t ze-!-V=m~hqiHm#Hq%+@rQTTP0@=(;hB<#p82Og#o1!ph>m68V6dMO6RJZATSPIH1@u=Y6we@kU%%0){;#t2n_Dk;_zIZW%k6*;S`gkvUTogVTo zzl9^La8-IvP#U}o*qfokwQ*wSni@@Ui?BaZ0J<({Q07{rg-(ocq7Nxg3PLXf9cD`t z6WfrwAaQK0vOkc!0!DIAx>j7sR!8mIHwL)|3u@vQe+@b*@t8HYTpNtI{a2lde+Pe* zlS#iHVs`~0p#X^w;qWr~h_!kE(jYcs9%+uvskG*X)MIa+6VpgiYagr1Wh{152*|1g zuAeshm65sgYXl>+gNJL-EbUvbIn3_@qWNgJ_AJ?&!Ux?+26!Ezz^5RaJpD!xBX|cr zh+KW6t})(*sDbU}Ul_3mH0wb2Vt~#i4YsTXe;3AIPZ9}QOlmr}c^eMH{aJW{7UU?B zA3q1Ohk!`s>RdLW+qg=^R4px~9Znzp!8YDZy;gTr`F6K--1qN&Ec7VTGjUYK7k7`~ zPvt}dArjkEVt9m>tAPQD@fG@iKLjZhplUaNt<857Uf}IcyU76Yy^4aO;{SHPLq~gl z-%*C|;2%S2wMAW3Lh)2JtR z9P=tQa5*_&sgbuc-Gg||q`?0>0cI)1_QClb*iQwu)graUiW|9r>+g5|n?``4yc$q0 zlbKqF;P7*-zHw@)u2 zDP3p4T4#5;E~KRuXRe-VYm20}2W>sjF5iGUt?Eg>yW?C4HR^IJ{)~Rvd5|o5v#t&d z4JhufUXF9Ch{XOJ2=PA-s9kwE^fn;pBw@KxC#D~^tOAb2g!Hf|E*>THC2sJ-f0SfM z@E@sLSo^cGDAY|Zrh@q-N=n>r7M!0RXhf#0EQte+%p(BE^zH3(utYj{GBCUu3_%R( zn9dN)U~xjgI~ipi$?}-SwW7Eq&B9Pv@ei&eTT1+}WX{nvxKQ#-MUEJt%MB1(B>c0W zVXR$gjx%r3-xx5CHRF(|+q@G80T1X&Mj?t4;fxat-|``!1mpd+#cd69OSYF`XidTh zbf8Xlwo6AZvmwmM{`~=_35ix#xf?j2Ur+wR7w}Q_q1JoFefn@lG_@UFy7GGX948-( zr{8&o!9p)**?7hJo%H+d@UGDGoxtkA-3d6%;#@bR$z38a0HN|!Jwq-i?84qD8ixC` z+$5)Z^6)94l}Ec6~Z+^=3s_5$06N9p_1)DG!xw3espYITwGIxY9;~6oOE%) z!2vvM;}%s`7>Z(?FkxkRPo7jDlB=iKxLryAj>`Z$7HPA*)SZxbGN%__=58kar}_f3 zdR_;p>{`%Hf_Wsl{dtyKri^X%vkr&jSyLyk+{a!sXi}V8Rg#8RwX#L(d6uI6S;!H+ zpQ`XxJ-~nJJmyj|WHVfx`3jr=o#T2T27*V?s-yr}NYG*&v7Kx$Q zq$c7*c*8}&5AP3>{w724qhF!iW|jL{13yE6$TxrnA0@EuqBBMdcNVM42D$=veFSl@ zu)KBGE#MdhhbS&C4y=m0Dwnuj0#MWRPc6((N>OoTG7SU%eDbG^HO4Vv>GA>Sp+x58 zlgExiF+SeE@Wcy~bXWI-l&5fA+`*IC*uhKbZEdP%Dd(#1`5@rPq`?__dR6Cw0y+w) z35n=t$t9td8(%tYdqHJrF5foy^$?f<+67Wkc^t$WsLxsR_JHR>HAP>)LG!a&H(OVS z+2E$Q*siO>e_tzomm9)9F85E;kV6Xz4ZuRHsYN^sy1@=QrdX&WjZhTN+i#W|ZY-mu z&llu(bM@Vzuv(2j9N`x$j*ZEf2c|qM(VRPhKwcytS~>#m2a?iZU031y9Vv_Bh=c!X zFC;|4LYCUVixbZWNU)8+Y6&LY{*HIN{ev(*-oN1J_5uk&(A7?eh#nGF;zeU(K{3dv4 zMnXHYFQ*v(eq^GXzHj*wKC)MS>Ec2M8|S&K8$nR!wEAFG4B`NtHy$3H+ked+MBX>B zHvDXi(2=L>+Z(XX!?#i^B#Xw;c7nf4oMh*$u0@t-FFdYc$wNQwAA^`_n?%9- zzb|xl;Wvytb*lp63f(njiz;q#QAc*_IXEKxpQ8?GfV253Z0!7vDitRTQjgk|D^SLG z)856{Cy8voJ84e?Q%Xu6>PdF?SbC42c%>PaP*@K!&)+XXRp0Ly(@k0hu}hc5?8DRy z@bp?3euD!wTz+0wwzxxjNvZh|B-}Zm=hq7gQfFs31H#$E;^i?mRaX3z4l=L)2G~qY zP{BLEOxWcNjzYjD4~P$&xhj8P3wYNZ-lV%w4}24RSKiEO%E8Lms@|5nkP13VcyiCK zT|t8QthD;CWd_i|MeyWD*SLs?c3KAlZqH^cp^y-P*cv&sThVV&w?m?7-pw}Nxrbbe zC4a|x1|=n6)BqDANg>~j=T=6%xP?eSirM*uGIBNbJVR5{^XnGx-w&Mt%ZcNlgE)_R z5Uv)s_!v$`=~Y3ChO^;Xx_i8fEfSItK-RM)|4k8_rWa^5d)dK+{({K(7?^|taK#6~ z2Bh1uvU0LfCteX0@f4{I;A0yHa|90VUrd}@4B00%5W9Re9>V@ItG826{+VDoXu<(1 zORyOSm`6ZdUI=PxZYrt>yO^jPU--1d<8DZIm#@H0VNu@7gRV`>R~QlVi+HimAs2(S z(3Y=#rVEob%g($HbamGLZ?64}4+n2RaN^!_Ah<9|CbJKUu<5>L^z>wle(8ZFS3Fg* z=~)f^J5gl4;g##xhahK>Umf7l_w~L-2kAS{*MA>>p1~3+A^rdHlA3j)h(s=19R;Xw=ShkT zKMkl@eWm_G2mF5F+rw@la*DcihlmJ3B5bRsQluink&ws$w&~HVv9T(wjgbw;+A;^7 zByH$hiFSngjHsoZw+xwE!R3(fNr8>6s~=5<`^W?LGd>dBTSuy{KI-ap_TC!+LLYv? zL7qA_ol;*v6OwnlS|!Dq+#T+y|Cl+n!Lju5S;qx2&ZbCaz`=b~@rc5*zoaie3Rlo0 z{OM9UIbFR8kppepvyKCZ!9{i?`AK|RWS@}P-`Lh1r;5gc#Cg@b?{){!!y8XQe?I^KeE$v6E^!H185IS)mHCs()Sw1nO;|z@3nRrF$ zGxt%99u$x-V(&X5H?}oD`SuC>#mGTBAA!oU_z>!l3sH^4)y;!XvJ`qCuGU+il1=w<85JN-a9AOLD&BtFpHDM%|%#b0wAky}j=K_!r-jrZVRc%^~uzsa5r}x&HJ!H@NW)`NjRbVTbwp#l7CbX^MKE_}N3* z1Ch>W2+i7wPUK(qDRU)<4X9ev=}viI7JJW_;K!Qqc`ag|+jnZkEWAIrERC~AulkE5U@xl`Wi+{=x&gRDXgU0 z?`awu3Mnc0@4?LmEu2ViAQ8HMGjwrp@F`{!|GsC3@nKy3F!LRq=Ck(KXJoeoYqdW- z+;oB3j?POka%`ao+SwvsZ7}C}{Pe@ZYP$AYw#~E+O1ISvBh@lgVfpXJPSwZo<*N#; z>(AP|&-3Y;`;VUEI-XBZj(3`imOPQu+iTVHuQmmr8FhY)N;K8=TyHV#7Zy7_o5k7f zl^GBY`!x#qc$ouH=v0o!??kLE6lG&AUn3GQKV6sEH=q;*hRNnZXkatRDK$w5WW>5%&g854Ik^(qyH_{QAbF2!yk+@=k&h6oLLa=r+4=?mVoO?xCHj? za$Pa410UZcGQV0-e%r(WIvsn`HNo?vGW=CAACnU!P>R{njuw#Jm^MtQVF@*GzgeKEMQNECY|=?|W-+*aN&L+)Fdm((zs<6K;O815IAOCI0si zbX{AK1;EnpHnNyGDU%S`@(E0?uh0CHvBa};9ePMCQTx!nzB;S8t%umOhYIXxuv$i6 zil|xhU#BfE3u`QU8J;-6%HI^v*U=%G7jmaogS9>Lf3b0`DZCs=aHX!R-i9FS#|f8O zW{cF)o-p<`6%twzhL|Rby_ei;r>V)C`gKasgDCkH>A^4lbFVbRliyvRWkU8NhJV0I zO($P&<42&4=~O2cBao#k2~?RjlaLAtrluVlX~;tCz~b}L9n0t?j3Qnw|4+A z09>zot5Qn_7*g@cQEyHQc5eOD%zESZ&E7LuK&?rjLy-lTMBWxcM5e?-~&dkkmU zhM+DO$?fr-{N6<%@@rt<@R#yd4ExJ~1M_|^eL2Z6YVCfN)fF4Vz2;`_<@A528}&=X zCBux+9Q%Bzxi#wD^0N0}7Ze9*9r|CqKm@<5@IAHctv|FK9bGYE`tVYNh-J%MLv*K`lU2KnvL3~(3!dCIs&h~av_33|ai{j|Dav703 z;L39OMzlof4plJ=(ob%hfv-OlGC+)Wl2OqI4w|~RpZrI@r1qKH}2!2@KEq-?pr% zLs<`wXBHQWvoVrlU)%1Y;1PO$@Upn$_pc7A`=On5%oZCt@?f`Kcd)E`Ghz_!G+*sf zMo&?ErHU-Wd~ z+CHJ$fNS2NC^Xu8mxC`)7<2o=Lh@u=O6&Xbfqkedi?xSbQkCLtkulbGAJg~Imry!T zAM6%0d$HLSC*0I&T9biLd)Q8dTs0o-=QoJmDppX8W6mLW>i9EH@j+D3lMoZsd;tAm zqJrh zEo>i3ItfZavaI2f3x~NlIoB8W_(KQN&ciV;VbTh$U+?`7az}iYIKG(x6dna_uQrG z3kr;ev3>5jaXnx-{eJ{q=(X4}tx3PN$3J2}TqPSVC6(iN<4i@AA~XyFDfI=GKcy&8 z;U8ia;D9%8d8Id`W)Ul}*rrYvT8Fc;Vx={=ai-6^#8G}#z_)sOaF(SmF7wZKQbngE z)d}(_!cGg7qC)~Y_Nk%36j4W@*0x109%Cd}tOYaEOVvE5$ET`Q9M54Q?FvHTP4Xkn z!7MHe2#`EC?+iH8ts*QOBfqSdtacQ|w=KbBcJEg{$a1^MO`Y80jqNZN3tdyRJY&_q z{S2hdv-6mqIwB=|-ZY)gsw+ug#{2i3zdwxf*V2PLT~3is6s{?QUYjFEZbt?R~{ggk|W}hy=>$Dhtr3$o3N|` z->2jL4G>e5V?zG`Bkp*sx1eEQj-1h5C(2Q zO3I2tc7G|o_<(F`?gx&|q=$PAvHyPXvQ{6h!_AwxTQwQ+ZER3VMg0z(AI6HLluMA9 zN5BhS56s95Ks=7m>co3hgLqIxU-6y0|D*Fp4H$=&4mFJkN6!VhD>FgzIe&lDPlkVv zsyOIE#KL0AQ!3BW1ad=S>9Oe(FBGA{XYFhJk9Sb_W0)fQ&xD(2gbkKoi4XXsM7-xv z!Daazp@q|lm>p<@v=qMg-%w4{E}10Lb7q`A&+*9bo>n)sLhQcCCB8W;0!hDLW28Jq zvGnJ9C1KnA!jHG-U8Ls84DYL*8Lx46t`af*o z9^M&SjJ5Uja*{VJ;%C;&T+p7aSU!I|09mFjn{|hD;mRSZ)y%s((S1mB-+u#>V>bET z-HSg`BXjd+KP_C!RvGuq+Agv=7D{KREw+tynW=+nAM@siQzSey7SFZ$umfa;^3wuW z2wj}}y$i#_M+clA%Ye|t^QKnWwbO(D*K7Xvf5HT}h|PqL1k$ZqAaTVZw5qj`ueJl0{=^& z8YA!c>lwYn($bbg9U}`1#YEJWQQwu#V|(4oLurDxXN23J@_?AtXZ_#k6p3CR@9E9V zIgd5w)RMjj&z}O4tG8>Mr8kZQ9c89wmTq>^{hgDGwZSZCYdB1K=Gr<*6$7gFzBIKr znGtORoG40%C^jZc%;jo=H~V8`Z{<9&jfnT@C9PbMuWu@tS}G}7du45l>!3z9tS%YT zA^)&xNd~WF`==|E4({&wbCFv92-W6uA%{u?hth%vV@}-&Gz*B?OM~*0W%2Fn6er$p zT7LXxjnZK#8!NfDc75VMH-sU z{?f*2{VI-7@@JzSo+jYrt-C&$ms#DjOf5e%gDo_c`VL!hC_5|;9lrQ)H<^|+Tqw-Y z)q@BjPCVtT?0|ArL4o`uzpw=277GRH3M;ble&@-utKZenCM$tau-3cIpxn}W{zP@&SS3G;r&l-9RO@LP`3#WD`G>rW>*2?odp}=Ej zV)}LEQ+D>|ssz)>tyfMib|_TUnM0TezR-n*vH|%mBzk%%33t=hXWV9PIjKjYerAoGXB$<}bBYM*8Ge(MmL-KxH%`*%F1 z`8I7u7?5c4&x66$*Z+bRb*d1ABV{c%BV^YfuLZXuH}{@(d29n_Ip>x3vi6_S1Nr~* zO9%^xX+7=iTy1|x5J}cisC|e{`z+1kqm`BsX5RRFY~$ulFn2k7fM+*|up8b)$9RV> zQ+_(0F#3-R@OKQ-z{iIK3}+WIoH+5vzQ`R%ocuU*h??t%M{> z)X!uolDw6zG8_l6vHAAH>qPp4o8}yrpq+xf^XK^;1G5+AcGdl7p zbSnCGfp0b-ChJ;S+5qQ|^Mkn*|Ki>MY^a}PeLdL%h3~Ch{?RkJ43QbvvFCDtkyq}N zFRARX_j~0njf75iz^S}%w`w~%(fWuu{Qe$7Yxw&}#fY>ZMZ{m?(ZHlQ&w57 zki98ce9TA3AU9KJR&w*{um_*AmKcNXV{pqd!`n^69mS2l@v;H59oc`-da<(Z8Sz^B zFH)L#pV8R+(`D`@@e1-ya<_3^%yOKFJM$^+0@?>VHczd$sMWw{`8zYNvqPR!rFYY! zIV`hGb)#O>rhGxca>3MY)k`uUKvnsb#M9}_=^aT)rvDQ{e{QL-x6!XOh!)~m8BY2G zg22obvuI#*b##ubqA){q<(d#crkuXct0!z1Ur^N)!>Ml{An1|bCH}JI$2(PfICUFs ztwzI|-ginnd$mjbDr@cD}mxEvp`~&3mb+5#oLif_+6W#5nzrmw^nOmyI!` zQ-jBI-|oI1$Oe6cs-|g|#@_|9;2Wa^glxJmhKGkwf;2UFvZ%|zQ>mw?r{vcQo+Bl; zW+`T{$4<vTlEo8bUz%7!lp--r{Sgb>T}G5WFq$UmftXA6)%K%RF;)ILFG` z1YxDa4)Nt6}#zr>MlJoCY{@gOwlqVGbr%x>A ztxcB54>eiYz|JhgtW9ENW!Egxy~XpMnwr2*`^xQQXlgvJEU_{19@O)d?q8EAB97ou&NKa)!tB`5PuJgE-m+)CdgX?wXit69Z0%Cu5rOz1lw0ul zY1E|O_!*SJu=`$Vv7g0zkL%rf74|{7sWnTYg1wo_RXU2_ zOfA>tI;B~~EkRppYpY>l@sUG0wtITzIX&mpk9XHeEN$K0pWrJEvnn>ya`Q|)uMBRl z6fOrtXNi{CLDHOSc({;kaIoTX^##eKRJGNb9X6C{EYX|jX<$cjuo&)06iQE&mU7#6 zpA29u8+bK5SKpx4MXxe3KlIJB-)GpdCG{eYq7?M<4sjWaO-q{&kMT@_Mh(=1m5TqL zkGjfVGC^G092~c*dM0aJ;;Y}^&m=sP&*JqkAbsNqmM&AE-tPF=~D#5zn*8&@@jp{aA%{-nOMGBL2|LSPXC}3^TCr?uDQN`R$cwr zU5(Bf=N*y-z3(9u-T+z|L3bbGWW49xU0d7CE`m&MNlDoMW9z%)ss7*hkx@xfp^PYG zld@%1vO<}0j7rEB4ze3kWY3ILR(8g*S0yvlv9~zLI!13=<2+yE zIqv(quj{%O+Y-_pCe;Uamvh`I=ymQgN@r)*G0n9V#8h~c5veEiUHG=M-D6=*u{M%h zM_^=Bf5ov+~tFrXg?MQG;+KEnymE4@UPE9SRzbWnb%6IR(vSwf~T9hjq zJYm{|fTY%Pa&u>>q4Y%=@NHb|iq_WFdPO$zaC%XAd?z;wW(7MM&ZEycBqUI+lB;nv zeEQuJ#r^&Lp1Y^V#>ct%`E{I!c(=DEbT>Xw=G9b*RPU0ys>(ctH4A#?@a^xE+g zpZdgyPU#r&GK!sH6b;T$=CAm<-PfCRBQdGJpGRl)^WqWY51(A2Sh|0K_4B4^PFx%V zvK_5YB+Q{V7h9!s{QUf+R++@?lZ35%lX`o5i@d*t9)_y zo37(8pByG5aJfB(?C5Fb{nPQq>?aD)Z7G9AzMmqw79XaZ9r_J>60~Gwet`(jxXcR` zD`=nOwn+%}VJsK;Uak(h<#^8f8~xC!+K4E$?n{9_z4GAA@y$$nQ&&;=6nYYy9GZ0c z^3!|x{*nq$mFRP_pPo{*f%H5gAtB-GDJ7*D|B$gJMz@;;1R`>0Kv`Z*mUP;DHLY1J z-%PorMBTt(uJ7{cw1kw7YtSz$fN5@-@7F15H}vEHKyJBYIB5Mt#nL~3?AYPjNTvJ} z)6RQ6J-wxz-HjY^m!Gf4TjDd!K(pVLsusn{c+urL+~R!?Cgmt4qwVzeex3mOi46$s z8g72zqH%S_J=vLk&M_Y`g<$(HSHT4SrXU*`r%%_0nm! zH+f~nDa)wJker6cWz(Z-z1ddNz(8_1cXxq*_bq&mq*c3#_!YU@InSu2Gy(z}R0$UQ zrORMqS+$?`(8}R@`0(+P)BcED%en^Cs{cNx_lG-!7tKGBZuTs#$6e$^qmlhw<_z{c zbJXFp*Me#IO}}svBvt%y>FBd9dMZ>!PMXY%;!!!PI~IfU@5PLpqW*$Po+;|StZ;E( z#V-!!{0eNCph3*dQcb=5tLZtbPzUlR?C4OGaNh8OknbEvyc91W&wWy02`|+12P?bv zo`XAo`O;o|wa2%FbRoVjlnwjt29_nr1+dg=Z|&>?_G##G?#iBaL(js}@rwn5-hitm z$Mi3lSLPbThAG#cOYVUf1S9e?_>0i-TVk%jTVE%t3rM|7mY)xTjcHOGLymJOopG&# zMye9MNN?Zw_kxb^G_McORxpgO>QJFVS57_&6 z1X7%ZFx9Kdqlm#ec#-h0p!<%tw(0bGZ6=7&dwSGuY%ErY3A_`4d;bCK8|s3T)ubku zRYx>Xmec84gZO;}`nkrw5bqAtBR;dLd3AH2enWEvq+tzV$%t~db(5dUl~bp zc!WW*Y#@?#vOe|Je-X(SVd(PVY_Ex5uij+*TzE@d$j+8oj`Kc(!>C*!c_4rY>vCRR zQi+2HEuu{P_syNV38;RE!tR`{b;Q*d3bU^ujV33u7XZ6ssI7nx9i*yOXQ;^Q2V65$ zM%<=2bDW6@4)<1|^om+u#gS#)x~`XBTgkH0@T|iQieCTz>Mc7i?tI$NxxTL5&BQ$} z2+ZHl?_SHe?rtXgGMy5|B&e>;h8<>#%r3s9m$xUFp3%*5CLuVi3y@RQ)}Lb~ew=)H?^K}K+ z1x51~hRLBFmC_}3^Bwoe&7r8n3_o3c&(a0^!~5>7G_bh$(?*S8_*n#ZvU61*(VfQz z=b&G;m>5hG^FI&(X<6QRH`xbX(he#AE>vY1n{3BEYpku8rP1rHl_KGfOO=~eNs}Nh zmfn2X-apg46UZ1g=-y_3?1n!LWDjj;$e2I*e9|6$P{#;AE?K@>5&3oHp+Sr8K zpQ=##4Q*3PFJ#9<-Wc-@Vq9o=0{_5+RG~(nOIUs{b2+Jm-EyCC8ve*rp52!$)AH^o zW=YcH78Ww?K#=17Vg(mgIOr5xw5dP~f4KDJ0%rvdpz?2tEeS`LOA>f<1KgcmHCQQeMQLV$8-h-3R3&T0w1K*;>?(J6-0{PUT?hXi z_(VSu;imMO!#)rKDunDumW9G`Lb0f8(ahk(D15+f&TukzD12vVH*Du8*=mk~4tqrS zO@-{#SldD!+KZc+n{EUIb&OIxT3P~z9dc$Z3YJ|;U`x96ol?0iMKMbMj!GKHt(#x6 z@ETYcms2u1t@Qr+l3%@K`1C$rLXd~&rS*Wz5z1XV)YJjk71J1mXpq0@- zw2wg4rh_XjUjs~d;HajDz=~;?L-MCL^&<6g1swyn0p|qRG!cIlkZ&=Hv(9#(<~0H~ zUl3y%IwRlB+~V!;4aPg~{HE9XKC)6<0BQGD-O;ewWm3|x1$*;l3+J5s<1Y%JRrl7? zL?W7KPx< z|6JbmU_DqHI4fzo_gtZuW%zs=o3b!wvwDDsqbx1Yb?=Sg+R}-3YaaUJ8SY8 zm0Q(h<%7@pVJ#2Z`wKdx9N%B#?0!GDz{KBS)7&-+me1L1cKEno4|De|QnK41uiuMI z?(DBm{t9px%r6BAk@il#?l-Sr@2-*|XPrgF@#n=wlmvF|jS*Na9o>(#isU|4DuTh< z`ZK`KbjU|)LjV5kEks&cIuxkNfgA?jHAjM#-<-Z|tC;h1b3Jr_%LH0q?K@n zaEf&Gc|a(a1~+~a?Dhe8iIa9_J&Kaa&Qph=z%pc?cfsmRKGd`z&xO!tXg{E~lUFjj z{r#=c>2g4(-9w1}`SthSaqW_(n5=-klkc&&zF$O?GFYwl6-jvEw>Og`Bgx5d5aO&> zsJTvYPJo;-5YE3>-Fy}8)A4IpIqq6pKa{ysM@yr}ovs1YI7CtV>qR5QP61=6Yi4C3 ze%Q?5zO6n3{YHbYYm9D{SXx?FTnF>0NS=_LjV`>NA%TK2;2~<#P*U^t`Sd&ps`0l! zB{lIm6w2~R8#OjLjJyB(<-2*vCq!_oYUD?)a0=#leGpz3^y--}-81hkARk&yiOt-e zm`sfyA|ntTFPTUhtpjS^d%JGvBYQ)i2b$?hL0<6BRjmemm^~Csj2L(E`i<{~hy$pc?vj{~&`6z$Fl`{k0!1mQ=-5AS*+2LC zgZIe$e?gOr@Ywr_Gv%^VYD*kCJC!c`D#^*s&l)!zB?p?GSP|{oH94Q9Hq!j-UeyY!9or**RIO__ea zti8&4G-PKoAxU~y7m_dKd;*(INT`v%m?hPd-uihI@a9`)f305vX-@8ZOnw;hP@#Z> zv&^|hK{4)2bO#t+sKml+F)@SU4=^$xO3~3-Z7)P6OK-`#&dW`%^c`sU;Gv}j+b(vd z2et`k0O#WGS#fiQtjy$+7GIIu=l0h_^d(0rk&yhmLBl!>!j0*^wqBmXwRU{H6~=!I zOeCtk}q~%2U`IQaHye0!@#+3-U554i9B zP_8Z$nDTq+%;NP2B?ZRv&Tgu2;nSbI064=@iOSb9Q2)@*QnF$C`Q|BU+WYsb*5tHG ztruA;c1j%=o3YQ24bD*PEH5;vvtE*EVS5uSc>nE%iN@9_)0S&s?bUvFsGX92{0qeB z|6D)!s@kkUdkIa+qVTlWb{Oyd{g(@<{Lwjr#my=vN-vdPUF|@TR!u z#pTV%UKML^0o24UO~R*&iUTtUt1nZLybZIyzk?-$4d*r$>^@2bhjAq7BsdSn0!jn> z=YkLHK?bc*^U}LNlnn^?aBw!nlS$=yRbf8G_c7BVU9l2&t(d&$+?XbnL{roKRzzt_ zsDhOXWm_7yf8GBuJBz&1&_*Prnn+T{3@t1cuQT7`1^!r&)COi)3lonh!Es&rhUpj4-R<$#C_@+7 z-ooZf_VPg~cin!bMH%KTKcz1p@Ku9-VW?YM-)g$h`Z?pAV)AJ$|D5x>FJ=+@kdtX7bZi;5J3;uk-xV_ z_;njFf6DFGZ=wcKi<7%S`~{#RadIn{uA5G#rN)Udo!9rM(9}FWB%otxPM9j`mL%t& z8G7VdN45dYduVPMW7n;ny3hRcXW%o;GdTl&Yy{B*|G8En*w{x+{hS1xJdzkCpm)+< z`w<}eJrHEg{lWy1D+e<`f){4@%^72_; zo}ZIP=or5*J1FG{o-^@-PjZK_1UWG3dbW9V&r~e)FIsc32{2no$IYM{7D9=FVmMWPVj z7&R~Zo&NeG6ci1ZI=P5QEb|2WH&a;=O)bTq9xSG-)R}_gcwT>c8-moU_)9a>9`4I6 zDQTHQTD1MTo_p)}a_~n%6;m}KaCXP6RS9H_I{M$Y3{zAi#+$>mv-ZYVURJ+xV`1Vn z^8}M+S8v@DR6|cX7bK>!i-)?3LH7ZkI#)n$(EE!jf&BbY!jgg;H%_A+Z$b|l=v5Wn z65t)jI^Y<#w6zFQEQtwuy6LGr%5$l7xItHC3u~1f{hytSt$iDbOk!U6Y`)3ls1rFc zL^fo&LaXOq(tjc!`0Zl2?-&l=h^LfM+BtCF7))WQz#XknXmVj;9#UxSFtMdzytx7u zI`KB(?-2}?i>*6+Ky`E=WS=h=Xj~oD4dRi05cfjhvoP5JLoF%vC{%uuHB#^F$+dsI zAOi0`m@d!XTt=wG78ZBPysWbXJxZYkeb%dI~n9wYXN2xlEK<)+3PtR*$Vw zB+b6?DqdZS&A=_oqr6&3MWwKmIym-1U8hTJ<{#t%Mzf=bxvG9+FZ&zx*x8gjgC_$< zX&#oyK9_i9m}Pkxo2jd=9eH7bo0p9_3fh7Kh@8Zo6E3wX7F)G7v^)Eyq%|%C2)cU3 zUtccXmU$DL1+S4&NU3z~j`?)wq%02Vs>}q6S7bH25xxDdCxmSrc$4OLcidqCO6_hR zK2^{euStx%^k%Jg>;oAcUFLE#CxCk9Va@@aSm> zt`F2F%ZOTK#0FS@{tOs5a12!A|75K&*f7}qn%~`WX?oS(9=Gd>%n<0MHBQG(W&CA| zS;L5*nnv8Y604q;HT$vSnSvT4Bi1rUvCC-4qc6_{YqZOiWt6bBo{^pu!jk-8F;tqi zg_|Lgh|s)W6p}-IhE0%Y-a_Q4zc24tm?$q77RW{F0U;(KfpZy;H>ug*lzAkW{tE1r z+ne!V>Bft}WVe(!oIyjMXVq6Ta8F}2fDi%mIwL)=v~gwz*Xpwf+gPsgz;+@ZC*rT& z+sE%d^dHU;47#@j(%!v)T6~NhU`gvNOdSakel8XHf+5c~yDrf^YiUF0$=WR3RUWhI z|IsfNBHqyv8CkK=i0=a+vDJN#Fi;;-)9SHNfN6uG>5}mM+uz@B-Yyuq6Pv=&bPxRa zem@-;W68+yHHSw5?Eu@0**C;a7p&~lsKkBTZ91!6pYjx#{dF_|O9hU9V%&KRG^XH| z>`-s6n)}CBnVyTWHLV63##+YYv}f}#*KlZo8DXJ7#y4>3lCS&)D#KWNLxkVdZIdz9 z4q}R;qt}4;A1iuIA_Au9;CHZjs^p!lR6R&~px)$d;9*ObX)!|~i;*i}IRmCd1_saL ztI`{%J}D`M_MW|S>|hDl7fALhu@u=<{Pg&A+q|6vcH{xcUr{)WM=Ao7DJU0t zfkgI?uXFnH5=N%F(uiv8ki&(SVk3?sZC`cpmanl_7y4n z__QRH6?f}>Jdq!x`;RUnFMrd^i+RuMTSM*hF7f-ZQgvZ2c91G^=%xyJd zWSponN+$vg>(}M|A;4Rou5`l!7BYUbvbVQAKqsISFOD(~SuBC5qAhj6JeXceKSmNL zQD^tILu&+Px$P-1EPYNgl)eYv{!QAVGV$ z9vLY&NKtyXqF_Ul%hqEaS9=g~~ma>rd)K zDW1|15rXyWh7k2xMLRaI;p3_b+L1*jG2xpJuP}tgSQ*EMGDY9w)~R&@p?bzA{Q{0O z-ZM^Vhw6cWqJl;h9d=Jpc=GpdA!7kSlm_(8g1QDQ^`ef>-YG4l*`m11x#g~_eu9Du zkQ?jjR@iugV{%pzgQ%Bzn&Z+tNE`RDKb}s{u&%UsTJf1fY2LNAqm(?pS;9g!`IJ7i z=k&;tgFP|eC0KdsW9`SOH1K&0)1k1TMApbTn#%zBpk&H ziy96UBO{AJ2$CLwRGEHXMUXpah`grB~ohfOKzVrs>cLca}1J|%FaA!#E zKeI*)W=$@b&>_-5$Yn+Yp+%*2Uumq@FbhNmKtrabsNb&hLLj&-R1^*k&-Qf6A~qu~ zf_mtF!bW(2naA4qhjWWq<-*zvmDGybf=4`L2v2wO zK?${+^?=3f{m@mUbM&&-+zLTd96Pg!iQf|C?k!_4sIs!=Xy{pViKDq1j(rf?JLA}B zZpB{I-KZu5PChGk*8?yS=kmu>?~f~kmGPF#CI)Q@WU!&RwP0Ow2`JY;xTYKX{_y$Ryi1I$8vS4v?TWiNF4lXz@dKQ6H_RUH=KG( zH4oJ<{2c7X(A>IK@ZGxSJh|-E*pU`3EjEO%vl1Mw3HqZlIYI2oC^fUJI{a>9LuyouC1jAW1VTdSp`(|3<~dREmOJcW5R&9iS&)~Qn6Npy zBj=#k+GA*UHMa_$fxP37NEB_4v$1^237AqfLXaB>Vm;{rnzU-3Q`YZvG4L|5JXpbH31B4gkZX_wQSqC%}nlOwnlFZ)w^{*=@Df$8Jn8@K(b0Q+PVa%Y|C_Hq@II;o7lECbYXrqXpLjm z8W8Q$!%S-}Ju7A^#8622JlD7a;XVGkZrPn?_I<*0lNs#a_f61YO-19bGy{#iE;b54MtIhGZv zCQNtY`(k2v7$zKP{u<1C=ScA7OMZSlb|0cU4$)G)YkoB_Jzjg&y#B}}R=L&7MfTxR zGQXnqcAAgf9bxC}tQWc}ln||^s+K_O)g)i0$eqoq0WlH2dT>@kzC}EJFun9(>~Am+ zo{AJ&kSZwr8^P;eek|l};CLe^w#XKU|If01PAePboqadwDH1px$iUeg$Jx>G8DmhK zRN9LT{P0?0qO~!vhD{xgN2slqf#lRyhL7QoaT)x+0^?C~g_{tQng&p-oxTi~mOefn zu+YkXx^%n)PBFi`?8bZ$@3Uk1Samua_Omj-?nuPTsLD3%8M!lqq&PV1t^2HaitbX_ z8{+?pt}3!?X1q zK*uK)*$e4%L6OrB_RHA@E5iQ`InTh?g$l0Q31cvf>B*0LB9SVaouS-Ya-q_@e{CLX zCe6M5(-#WV0;e?fEGFacJt7;tnO}=l7U>^`9s3c$XgT0CFz~M(*sp1mbd*qx)vEqT zY$M#wWjKw{j!WjjePvxrpGOeLT&Kz+bu(wzZ{8cLjuNr%Q92&9@M$Gt!pfhiiB)G!26Qy%w660EXxT?fWxBZ(Flwf z%xAl5fbJhW0Q#6a?IQ?bc_(8c#*kaSuF%+8WMl}+YB`%}ZJ@KzH-nk@uiuA!9>Sc{ zoa8j!jDG5-8`w1aVCcsy@&G}SI=)rt@p`GSM~oni;=NI~c9g8Rl> zw2vRts98v%1;Z*q(yilYP?)^V!kb=^=dx?vXpFD*8>*J-^h`!6liBMR??1ioW%fr z1Ay?FtV-ymI&shH1+ci(R)_c*CAqd|%mn&N3fe7_0bAaBq@a(y^YCrS>ZnVn%}1`} zIN#oL2m|=5?@tW`-V7Ys458Y(<{ESjq9)OMyIX5>11S!)GRQe7y{jRPo+5JQTZ*f;c(!bi*FVnPzHAI*OzmWrMDZd zChmBx;049g&s%P;MLax5exCBJH(?et;n6e0HLv&ACp|iPLx!ZxqhJ#~qutk8XM>3^ zLt`%Yjd&jsWVX0|U_Tv$ObszL@xvp*vTTHRLj_ouJ-gMO$UIe=iW85(?V|kAvFQ%@ zd=0JCg%6gq+avy=Lq_wGP(k))9M#Ie*d3^kxA$v*{{~HO-5Y*wuXD#gQ;OLUrqjIx z2h<;vcAng?RTCprc&ZCAh5;|5R(*(Hp`hz|Nd-)?^NBtY!6__b_QbHk%Axh zCi@)@)N65O==8bjALWxMtMTPF=@*S9-uOg0#?YMw(3syEUc!7#X)?w#$t(dfOt~2G z4n47*HRIt;9{qcSpKS*8xv2*?mUWtBo+>kE-TPv(I6m0<7qak9cYpl{DvwR21TUL` zy6YsFx-9Xo>6%rZxxV@N$=yi*fP1@t&o}sj0WvRK-4Doy*qKYI!(6PlNBxWm)srcJ>4xJ-#aabc4+w zql$_E_XT`mJSXFd7n3LyB%@R^a{u7cVUf)N&@liH;=k*cFm^e(5dqzst?B#IKsttP7Ey-C7;0lA z-<9$l(=`DMV_$W?JcbHt@pG(@L|< z6Phxr2hTBgrG;sx9tM?U`FcuwK^poww_=tawoOerr-~2C1CBfEkYTf*DzbayxX>W~ z>G``zc#Ds0!p<7%+)X1GM{b*WTaDFQN4w{D|SwWS*m2XB!b$^+B)SS53^CD z8+q-TXX50H?dZ3Qnam zdF!5KV^jY0UkmJQ$Vk=&1BUs!>bi``yE8Y<=kH8k5^;Q&Z!5SonF_86*k}PPx=RtVNmQXikmOnG zK^~Ci_;f%!Uce7)PnHGz2l9Y<^a(y`p)KWW;}hi??Xq~$o}QLK9o~^ek|V*Eo!2bd zfca^zu3>FsmLTYyeL-$-p zz+17{WIT!Ao>9~9PfI8!IuqxRR2z`Y{tB5v_v#KSpNsq|+mhw2udna@umRa+*u?Cw z#E5B>E-0CmR?5jK3J83ddwd7m26`jaX#K6&miT0{Q}18*>lo=?t~zf*sm9 z3(2p(qFw1jY)+L@(GVUj#9`V@H`%U{)iETHmv4<`LG~RLQeJ2`lNFoAtu1PFMJpnK zzd6QaU{on~;6Q70yya*zy-@nrsRIY_#5jZl^ZR-?xxb!qdRR7x`<-wvCZFn2PNl^_ z#F4YwIgu?F7oQ;K11Uw4c2-=~-PvC3WGeV6ON<^$)8;i_x1aETmrlbI?78kUpMHDh z>*>kSpndc?dXY6(V$Zqbo?SqXjraDJmt6Q8EV`~m6)e$7&hKI%i?Ihk@z1mnp)$`7 z&Z32a?=s?AL`V0=?7q1g6aM+LVup5v!}TmZCuYKuM0JhXZLXX4p!P4`jHb zM|lz}Trn`vnC_3|V$+b{j|Io8C^0T@85btshiAS=MTJ%7R|JcD=fO#|&~?ws@GuPv zGBJ_b44V0Mq934+n4j;wO5PbW6YqQ?hi)7up|JH#BK-^efVDv(&sq%h;Sl)8rT*U` zi0nVh$t$l8&7r9~8q-ph)FjzdUh#OWz3J*`x0~+j+p1L;uSer&29rIc%ok0;LDc^6 zi=Zg&%;1CM1KcU;(Gp$Q=3_o&xj3KNpbNATX;H3g!|sM z>#AQGm%2uBevA0V$mtoY{(JFMWRy;(RZoaHxtm^AEG+yXT)}Y6(B}%$zR9JwWN4eX z<(ZR_ChT`L3*XPVJ*j4>qwzRPmqo~m17l+_^Bp~Hg}%V76W+k>{Kev1T;o_1JQP=V z6=Ff8q`Cr2{x)8plS_$C^y|y*qsNkSs+>|Do?x6X(qEP0`JquDq;gLi>hr=bRlbfw+(Amr&nLa?|7uowY0%M5(E>o>?s zM(>)TR*OgJn#5Wr$X`Rj09xYaOMs&ba3cvvwLbMvBq&$yOj*ffD;}FJJZU9k1H|61 zrxD}V-xu=TbXW1%T}1W{7## z%07m>X$KY#^Vp4Lp`zwtw>d>Pt#u41;o&a3mbRxyY?s)nUwRZCLEV3?B5wzwKvOOgulkH?p-r%u~*_88% zbsmZcWC+PF{s_DL(-H^X9};%27u{BW+@8)ei5OxL={ldno-lJw<@eA81ezwqxJLD& z?BrrBHtEG7n2t_1mAc})?vS4*du+l7jERx#GwmI8cX&R#;TOa5^ey7!tgVxEaJc%F zWb&75UDF37($btX3apX&37=5qgEh8hy#iHOP$V7gt#A0s=LX9<`Cm0U85dIAE3cgg z=pSEY(Npa=?%a7RwK}-rU&a1nQQPa;qXqAL@O5ri@AkOp{zb@V$;@m_NQkNf*S9~H-xC8FJ|Q8kqCwXT=rV8U zvAx_SzPq(3bhrM9b#Fmh&8YPDk_H8X=yiwjFE_NcBR5v(a=w4^owiJ^y>Ru4!tO@Y zQnLuq2U}*I57pEv1zkL|y*Y&C36xL$#RXtba4}F3g8T$(Y3Mt#!p-Bnk<1bjjsv5x z-)HF>Yg}n+&rb#AfXAk_!qh=>+bZ7mZS0S45H6hOG31#Yn6{CD#7Mk;eLF%zT13a< z+sB@mKTkmLF8w1P^J=Ttj>a)|)%GOCFx=w$(o&mRhC!K=>vtborHeb0sR^A4yIW># zY;0*7sj3@w(mQWd4C543Z=4Z2iknR^DDvoXA-p;=iAhWCUyHb%b@%m_hXbXG7>kZffsC{?tT!QR>_>gq(h50A*J9^@C&ZQ< z#U{#QEv-$X#(!lRG9mYJ$VEHh^?^TYiTjrb-BWSKZ zCE$CQ5&OpYstCR(KeeXLf4y($_+pC$m&@91>aAH@!j4DP+Y{1M;1V5)FG-bAyZC{l zPpPj0g(0QXz9ReZaB8yR@>GOailBtV)qP|%Kfb>CT0Rb|P2HN;=v9t}8ZXacx1K>+ zW7XZ~f!E@G=t;`0x}~jpyt5iekM8zCMPL%`E3LU`;Em z+&XUr^&5|ba8{9`NY^EfLp>e=!#>TT6<< zRQg=it|70I`J2V+eUv|J*`D;{D>rRAI1~G{cY~zV6Zk8?=0je&B51=GCjXsTm6r>oFjPk~YN zIx0xgspx8etFl2^_94Xp&#I+*7U$`$Md`Nn34X4{?l*H4sTv~ISaOjehS1*f@TIXR zIzii4ugVuy88dZSr|qx%NxIQZfr!N*@oKYrSN2ee6JwQ;>q3J>d%hX08Kaxu7n$5< z)Wlc&Ka0w6v5M^5D=s%laWE?~r93vaR@OdIN@v2n zwOF3&FnP6GOK*D*o1_TN^=)#r2AWg%+0en3UD@#q3k!Y~qU_yeIsyh|>E}+%%A2-? zzkN%zJ9hC%u6xOy7AcgxO_>Tw(8Uq7*cjpg(_c~um2@NHI_+{x^#JXg?|#gWQm+rX zHSP}YTW^)f>DM@afyHs~fq-85+WVtNFRcpMeIUWKr-d2uSLr*EW!LK%X~F8BwljRy z{`w&|hC$pBHiWJ!P#YDcfdDjHpXCUK^ic3_QkWxdz*#bbaLjGFLt(((p+MMHDlKIM3BpxSE%8FP0-ug&9j47OoLpQ=s3IHQ6&FLpS9*n3y5l8jX=yQ{ z_urbf#Oa!fs)ky0WgCnHX!efQF)*vV%6u2XLcLrktrW(tOhsj4*rX9Fq8$1*RZVAU zG)Vc|?PaHg*Bb1AA0_MNTTGTt!$EOyeiOVyqD-4ZAx#yaH9Yav92A(n$;vM-tvj>v zsp^%eryG>Tc~6Q>DERoKS6D;JH(LX?6a**D({EcN!g*M21yFh?Hz-#~GI@I)&bPPlA#h*SZe&=GB_j?fz z(J-a-QfZ7gE4wl%wX3#9&}>@u5LJOVNpdsOaea(1Au^s9bMJIShu}8~sf4BNRlEVB_Q)#K~ zWzM$N1EpHjfMfu6Cr}`mOo`=kv~VhHFUeO%N1WzU1z^uIPCMnty)=1B&I=b<(GSiFX_exR zrrlscLaEBNOVB5j?xLt*7sS5H(>dHuhBnz*yn3Rjzs`FCEv;^FEPin^5q3B|uied| zjtVztkB!Mx#6?0?VpdQQ+bX@AsS+!^?X>03U-^zjKJdqQtgZHRXO`Eda}#e-G3rON z2uc*cvzhF*+c#jTrL7w1xG@Pjd3C**0*BNt>WB<2?ldp2$pDe^?4*Oy(ndhQ*@Q5W zT1rx)ueSGTOsm;66b|g{)YX^q2%c2nm?miYqATJx12j}@j_LW)c3pH<5U`bGlO`@F z!y9CKZH#_@ndtWjyH`bIAc@IyO%@I!bvX9gqybQRcr|2X7nSZw!Z%X9a@ zuA$qk&?@;hs1qdS_LOjjUIW|HTADXx@G+KFQo}D!8tNPm#@*#)NgPQeu?#n9vWlCk zeuxFt2Ne~y_`n=+yO*JxWo3nCYT#ZnusXw;h0=sfjTl>R#XK$EwA1Qpe3$(>>(TAp{EV9enb=aM#p4bLwi zLa(Ust~~Y0eAo3cVS~l2qVjCkYgtAxS?^?Z!**%Wk^YlL!U@c29vlny_X}+iO(bH( zCHbX3Nq+>K&JLaA@1G!5FV7}5Sz9-ojJ2I9Bu{?w#LqdnsX5v0ud)e2-5F-u%xC+d z8W3_dsIb$FoW{iS;`IH`LtZmj(usI(n0WtR&WVe-5WE2Ny(Z`PQPLzAN z4Nv?J7&m;A7#DYhnoT91i{b>cfooa;I2ls++*F#pCu4(CAlLF4<>)>NtKOd$)k0Z! zLQ)S58lB z9OJW6df-5z=QbL-0YzR^sm6cS1a$LFt*JrCO_HwN43%R|6~5vaoy{}#+FEkMIHB*zFv119!K{T5*$`l z3O#?pAcr$)&_f6I+tN8HSf*l-6pXi0Zo6nTEHpzO#(&L>e@|@=P?3a9b%YIi8BKka zEnOQ)H0Uo64r9UC+78V6fvgh%K9jpH+S;$_gu|aw7=N)4FgHgwx#178wh{5O1MtH{ z_UhgSxX{oUhuGL@3zgHOtICv89Lsb3@ow2&9j_UTJb`aAR&T9yJ0v8sq^0rT7Q=rM z$?Kq-Nd?>=Y<`4ncp$n06`=?khht#O(MwWeQkH{lOGSk`JkAQbUt}+rhMp5}D-^VQ zO(O6ZhnC6KU~jVV-1Q(JTb(htM4!yx*x7^%fC7S%us6dIkM<4zRV5t%xR*Km;(I--3Ou);L(P^>L{;3b`jY+a zY#RfpZYPTjzBfv{x;ebhjq2%P3fGMCi%s%Q_!$`k*`Mn~47qevw`a?c@85uC^1LTo zwTaIkBEM}ttvx*`eD|5N5G!lYoCwDYymiY`-bNw@Rb- zXD5001H!busgovwNyYiQRlC+^qsScRU!Ja(_=i0s?ueU>2)+X^vk_@MzW2MQXNOZD^Z-T=|vad+D>i2Px5EN?8s zizUY167UIBUqMKUD%#0b-eV~Q&BP$^F=Q6dQX;!}@jxpb zbE$+ZLUhP)8m3DuW|T;dW9>tF#>O7IUt^9jf!p32_>b-j0LHV&hwCn zh6d(5^lT=|-=g*W16Pu*I7 z*=1;1$E%0)l$4$7)3NALcO9jeSSepMBoFNeiLp%_$!)2%YPe&Kn;aFZuZ%~vl7Akk zhp!Otq~}d2)=->ehErChsT^@KDgRYhDhljF+a9Qk7|qtcIiwp(1y`Z7e{S zcj|9B4ng3VEGi{AbLOJD7*gn#_aeMDsHo>H+2LYT(7x(UW%) zwftYun=#_J&OZ`h1yIPeIZ4Wcp$DIuV8vikOpN0SKRMf@(Oc0MdR?pGF{R#W{f$Hj zxsD>c z$H!e)3!ggMR-Wvanw;$Pn98m5bAGC%T3CDcf+=xP)hOKj?N1Dr#u4$>mT=?lQs$qY z5?qLpbnDfNsLkXaKivj&iSj;M|7wd#TD98 zdQfe-i6C_GsJeTXLDF>aB8m*!h^_9|zI17w@xLXF>gTW)LtD)(t1qx|pJuP?lmQt@ zF1BPs8_H^c$wK7}Y!@VHa(PHdIwiA>q(SlEC*75o9H4P1Lm;E4r_<0HryyVS;ssAt zpZ2>ocbaSZWy0Q%V+C_t(WWWWXtD7(zM12=yE)ux_TWu#Q_*2qNoy1i+K?Esl;n8P ztC;hp&PCNTbxeJ&`$%ur728&Z05#loDOeA4aA(y{>C&U^Ne=F7e>z(sQ(N_l3}3ja z^nmFY$wiI4qkhOuKVgEL3W#*1K!2Vb2;7|?#czYfK;+Fer)^jA+UB^Ez%KP?J=<%Ue@CvNl}XC#&87d1 z7fP=C1xAWHJ5@dIZ(#4MlF`5KlboEQ;*fLJ*Ky8<-^ipk6Fn2n+R8h)sgzB~dZqO4Y?(+W5gw)~-5`|Nq z#Y@Ih9r?ju3e0c+RJR)9^Vlg#9MxhYXYkPgQyxBhLbI!3p;om?v8%zypj>A9<-Ma$ zmY$)`v6VurknBo5@wtoigyk-|OB>UWN59ER)aE6hFfmm!D1EZhJC>$VXVKWmwf^Am zavwqX3vc~*S{xLb2gJmvk!0t|0UFW9FOI2a$=KMHp@8KuLF(C3Xbr|q3L*oVJIWVq z;wqjPxl`%K%R)$^JV`-6-W}=Vvr^^*EX+$Uznzlg;XH{q)@Jg&Y0=kt^+cj3ApN^* zzQD+U8Vk0GUm2XWJT_bmbX}AbII8yiet&PY1Q3<#zx(`IH}rPhVds^cYclw^{+U{B z;hgw(9CLyi^ai*CKkZt7UdwCSa=mV4nmyiL>BI}&cuCY$hq6USV=k|VZRBCbgH_&f zt!DAFL@_bF@8859X(22D;S>-^%kY4Ctdz#Q$E_;QRa!EB+gbHW2FIM%>g6sJnOHc_ zX<5D8OXBWpH52v@*4Bd;3xxjKoQ~k1oq3|CAD3nG;u$!FLAl(I4EOeJl4W+tpv$MD znz#AHbY15p!HstzsJS5oF*Py}w$$F44+#;T5)i`RjwmTGT;ynuomg|}fSl$NFEcGI z``ARE8+C9}(oek8T0M*Kggp?hxDP02Xe&M@?YTRl8qf1{xm`ne_N0mOwE{PjvBqNw zaI|&>|4k+$_)HZ{j%kVK^%<*;?x3L06w&~1BxrTBJw{7Edvd(?MaarrQLz34z;^SL ziu#YP?Tps;C<~aWj#(aRlxNc2u&voIU)0TQ_4`UYA}X1B~{t%)g;JA!Q2)fv|d7GJ`O#ePGqbt;rMcW^r&0Se8WXw&dZ<0_y;;U_Pxefn8fE0wY)gXrc0kS)?|>Cp?=EknnnLj zIQAih%={8>*)t3z_>eko9i>mceLswevpqe?kDHpruj$)l`#k*X=8(l&KD=1cCd(d2L}!$I|n14y1y^vPx!w^eEe zAEe?YCcYrtAUan$IW6~H!0sXKGySq3?x^Vt_)nqT%hQinLXdPmk#OiJdP>2dOwYgC zZeeW{SZ4rilz66rt?+nrkZ`~uvodE?UH)`Vj=K}BJR58GlkY6@e$xNpJP;^dm1!ZD zN&wRvkmBTTW}|dUpr8^Xj4AQey7k4PuMp^3;TKIYum4|p-yPLt`u&OHAdU_=7DS|} zH0dKqZ=$0Zklwq}dr2U4P!t$Z5dlFuNRt{mBs2>cdT*hsK#(rIgt9k&$5DU3v*+xd zv;XXF&e2#%-uHc;``r4upL+!w5+E~U(-77)KbHL*rb93TCRed|<6}IEab&&WxXrE? z1ByNrtWIFyfyA)LQ!wi*&%nX&Gw^l*w~HTkDyh8PvqHF&r*SH2h%^X%pwBgrJ$%^p z=6=^qZ#_%qkH}04cGh!KffZr~PgTTz<>BNc&&V^=uHCu;l)N#qhOWI@P(Mu&JC1HT z1-Lf5&$KO(U2tYk^A+9JYe-86_Rzt@YE&?JooVB3>3xt(XxyH>aWFj6+$>~c9#xuu z7iw{*PO|PUJFsG!@wE+qWmanfISgSKr<4 zDzSMpf3hH+QE~kV^gJ6ZMfupt$D?C4%N;@djc@}3uEQ^SYj^73qTdArlwzzW z3ylH4el~iUln$s|pv~J}i_p$>-VK){V7mn$?{0ek-Ra?7RoKjnaMjo5nBPaqoXRg$me)@z5MG?=mBh(pW_bjIxBpTOYEh?=~G`ajtw4v_N-6$(uWr7Jbm@2%<7gzr(?iDCB6QF43{k* z8{}JmeGt%3j+#D?BTv~3{F!B=5iP*RXKa5551e?L9uRHVY&iAm$~ z3vsjH12Aju#>d(HTw^A$HjhkFG1CMR$!pP5ypTB3|S`7p%Uk8N z35>LEF-#0Gn)#)|@=5wJOwC|mtIBGZ;_1D)F_W3WUS`rlWtbsOT~IJr@^&x{I6BpA z9174XP9UtKAo=-|x8?kw#V)1~Q!XuUYAoD}xpb**4ulqZTmQCvq-_ii4SV#>c4Z10*{|jKA^d66-YYXw zP>zE96SRFGU#`s#y%?e8Ndx=kE(WF1gRYtiO`XS5n$e5k<^YeG)S!!igg%_+HAS7l zw}GxtQP%(nar%i~Yjbh3bLx%J-XCj=6_DAWO=>5O=NZkm_=$_F+vf^-Bh(j1fyzhT z;8bAYggI%=pd`!@TfYSYQhdk>H6>BI;RLY*yD7Lb#je?OiXk6z$S&s21(bx7#LxjtK{R2i%tyBDzQ2eUev!7Cnr9b^$FGjcT+ zLR(pU-9Uds2yMOzP8~g0pjHlf$o{m4!be-1ijq*Md6K||x7|hmstf=kD1tHiv_hEa zdC?2)MyuTk1jV9)C^p}%bd)#FeA5}ASO9Yio9T1&+s`*j2Q)5YG0d<^Uo>RI=wlMy z7>`=f*04*sYx|7^=|{(A$uk3jlxwR1Qm{qM5Hao|ymnlUj#rZ$!>CWx?sVa<1X)+j z08*qQrCun~s4~cj3acVh_#8%Yo;U&d+^-ze|K1>3)jsD?;_WQ3)%xPSwJRdo1)b01 z@1tJn7u8{W`cBV2 z_sQ?nt5E|xW@$AoDm{N|n*a$gENAZXTdiwR}J^2Y>B2=y)5U(Bk1<9xHVRZc8o2H=n`0#Fg z^ruhp)91>4E6K(SGHo-xISQ^Y1p#2zJ3f%>p%Y00KXRax=#M)mB(wwUi0YsgGL`R* zoY>kD(ch>9okF|z`~uGxrM|3))i+dd0$XDbOYiUOf8HadLc1GfNNam}Oumj$`Vph5 zaNwkCbGc7N=U-)~W7E!T(=EVs2zL5EyZ{{iimwVD|DI(ci^+La^9?Ez8Va)tzP~s@ zlG&5mV`z|&7?WTMn;kLOUN@M2eZXoXFF?OMiXYbycqu0^5E}W!yDaZX*iR|j@#{h> zoBD_HI^PWh_}T~ehBee=9m^i5QvUVVfZ|@OXt3L;=OZA3P+Q&t@{?bNZ@>A)W~eOe zvCc?&du%Tdl(-E@YWq~>eH5`27Esa0hA(A1D%>n^BMAPaA5>3+G7fnZQB<7Ap!MhQ zk%qMyb|!Jt-+s4-Z7*(zl8Li(cP=jg4h#XLx7w$be%H{GX@c1D4E!|cD9c*uMXcYp zv`o*}DbMez-M`9bfYxn|MYs{c($Sz^a930Lr!%2!( zJAaf8rUJG>1K1$Rdm=It+S&MmVT* z_S95ER(Z8oN6rXncOWnkF$zjt_TyxWx4UjOsOCx=%{DaA8hJzmW!s zhXaQztlskyhdcp-v;jfuA>Yu3&}#XETtBpvw#zE!=#XcWJoq&(fUomMMA+S~Kf+c3WnbEIq@M=H+g6qX z*f!lb8Ia&m)cQlK!?Hcf)HDqyRSeAi1xaJs9o5obkZUt~3v-(Wrob&)h)?^f6vY?P z(%1k3OT-+qdHd@S2Wx8NL6{qMOtxexn_tqk0Y`YkA^^-l+b&B>&_epfgjHFuqNA_I zSDG*N#?4z&+haewd-O2hqQ0K8Uv8n_Bt6ey1jwsqEO?A2*br)JB6=&pu(HGA7r8#4 zvtwyv15g?DcR_8m9*=W*4RX{W#BcdrSYAhLJ$-@!7>9S)Pbgp9rer!(JXl%YlcfPY z##Su_w`XZ}e)Y{;PD|HoD9iUFn(0HuqM%lMf z#bk~0mKN>~ibhWhT4F*ibZbYo%YQ*;#+z~hcU~<$6dg)@pI-RXR-)N78BONotVC1R zG`1ylWhUWdj7we2AZ^;u|1qSZB6Xw#=0HuD&+={z+Nql(#&jJ92V|*;qc{H2J>%5J z+nktqj{W*ssR3dl4t6$fVrJ#Jui?9(b!GvR1uw*b#)jKfwy!`Lz37clDYK0HuI?y4 z`~|iTuzXBn=NyK0u`4K~y&DfC{|xfj6^DmvL#F$bw*51!@){13(jb)g+ip}xL8|du zkZuvEup-eIAw1EPhGjuNAtpv7;L?S+rHU1Ar;0mal8xfV2q&KrcY20`Qe2dax_US( zghiuGz9e2YomgV8$QUywJ6 z?++QgrUkrZ%AuOId!6Fmj-Pv*yR<1Ofr2t5MpN{9()HEe1%v(mt7I4j;B}d#F7EDa zh?o>X#d>VNtfynCtIPhf^-x)U?~53{H7I4E6``8~+BX1SFTMPCPo|1ECm_RX3&vPh z*Hk21M{!&lq28w3u32&iZR-9`#;7F%d_h?PaaLNQV7wAd{geg?ig6H=6s^_63j~;a zx*yzVzuz>)0|C%8cKvO?I9`WTB{wG?hsP2)a&-jaMD+-Nn7FO1v`g?!nWcZW1?+*v zC)Xw};7+w(VfWwDBj?SPnWjS}=cE@#48Vc#uBBlLC$_n{RY6uJsyQe7KkbI#BZCz` zD8|KwfOPR-wD|2E4{siSySdLBLms`&{KcLaen1{UzrLNOPOabVsXF|Sx3Tf~)p84S zU0s1+Pg?&Fms9)#RC0DuJUo0P<9>V`s1`-N>o)`~OB>>xxGzZPPwm;2WT-^9iOV;& z$q=_r^8w^74Up~vDzOq;w%s?pJ{;f@=^I_F_BNXT3!HvCt=}7j9qk2lD$&4qLy*T9 zUax(1%}iVVNf9G}?)Nud1N%*^@OgTSgnK?rs*4D5)LxeFht4Ryz=321rTfQfy<`0F*_=w-)Ijx6vam2IJ^W}Nf{b0;Q zv1+NI8L@_8FCdZ1(UC6~sYldYXX2qlX^ zRmZd4WjH2Mp@HedxcekB%S|kh$<#r5Cpo4n*^EhXJw{ocEWhOhdJ7virQ%`+oH}JVISF5|mLn z(*!7@mA-O}yYLU|MFAC8L$NPgz;e#Zq;Z@<6vz`7+yV7sT+LetsAf|C5i2e(bqFas zQfj54T~0~OcapZbCc(F?1exy6zP&4d5Gkyn9v(>dl+ne!(r-6SL-|>hOw^qX%fs(; zYSv>RJb%Juu!I^Pubu~^cHV84L)hk%5%rHZfrq0^6QXaCr>|AGf<)R=1L?>`Pc4nD z-Ke`jmP6EIX1#C~w}4BfZV3wY$NMJmdKWw3=F1g^POe zF%3-*uiWY^er{f{7eFUR-x3n?G#V1bg2gGs4aK8$fq`iX(KR`Ju-J-B9=NbirVy=mX&y>!8B-loKaT@@0Mg z@S@ia&)D(hUGb{#(;TBDol55v-zvw76y%iqJU7fQxGc(`z#wun4mf;%Xda>X7!2$G zcW6|b*fpq=ha^OQE%i@T@(FfX2K#NL!v^TU1`L&{kJVT(Yhw~2Y(#tL$5QszY;pWW zE_3o3=w}HlybC%#;R>B+p7SILg!fttdIO(Rvl{-~zfBwH{NAv(zz5y_45C2`u^&zMd~8VTg3$St zhO(M|B*44r3dE7mbrdSmSj|-4yMWrsc@`d?=2ZLKZ<}kg+HdPROzEZe^Dl+m?{xS5 zv7*ZwnS5mI(%@={rEAb1L8lG5bruewZ*Wm9x+s=cbMl7aGtzF-8L^exrvG*__tHrDn1qh)Gj_!^V83Q?JnVcHOPxOE3S<&Ql*IypwR$T9x<5}%zb-Fqw-O&xeWJHU;sctHAED@f zMULC?2o2b6EG0Y(5(mX15VCWFuhsc?pz!hL`dT*J-=`vjVIsPb%+O3a=XWS zQM`N#FeLdv(--nEBs|gI80HRaUr++yBA6sQ%>0Sm!)-tv!~RS(W$G$ z>=-CiLpHgj8>-d0_g?@;*8$|zvEBCkg{$Nt+Q87UM>07o$t(u78qjVL8~|eHv={QL zy6jyB95Bx8fN}y%gI+hC@nJ{Ics(9MwJULxl&q}RBuMt)W^G`8498W00Q>DjsPvvQ zny5O`fFK_m*D!-q=?5f%X8F0^l#J^>oXkHZNzP z&HXscdkhUl3jz(cUXCcy|6EBwpq1Dyy zOW*l6d6sN#?gB+kU|dDTvSdS^0U6gOY;z(uHk9u8oyHgJim*8s)6#D887Le)RN)n) zmTI3M%v0f8RAjGo>vzYbv*}6^f96v7$H3|}^78A1%s_VJA;k;qnIZbk`BuaA^j z2BKMt(MXlJKjmOby>cYBKyp#_9G?NO z&R&G(IU{!joe5*dN5F6Z0Dk3ra>5#d9Z}p4G+BaG4Y#rU{W4}CPv|A9RB)W z4<^E&Feu)q((!AVi4{KG1-M!Las1Hi-uh5I%UG?+S&^2vHh@Zh_%H>Nr^ZUo1Jm+A zf++d*jpm$m8q}*JV7u1M0-P#eF%2`BB07Yr-mmrgM~K)5|>Q<=3K9} zfFZkmKbtvS*e*yeWEFJm(VmLjAA<>!KvWB8A^;1Rz1OS>jXXuFHZ{9X^5wR!JDdfE z?)~oo@yZ{-#>8~dTixVLm{4}OI0BHtx`)7bpuR#B;dfs$g((H#rBvtT+38eDCqzBF zlhpf?tNBN%_z2(!F-U^$@5lpBxot1^9+Z^=8wShPGRn->798YCfm~~)?WiLL((M2T zD6zMA>tDOaJ>q=7)YPDaJgH`uTjw}{q@k%6`01BssmPJ}XH_oYQY6^{^fK$YI8BU8 zhbX;fyXnT$z5VqC>48~X8_VX3v)1uHu`4GZo;rT&ZBN*8O^CYCCkt9zc~ozPdjDM{ z;?eV_6XmBzmIH=}+LGe>Ii3ieRJB|E=28K23Zp0FC}|b1M3T04m*`bLIjf0Htw^&l zKcy!&Z~4fMElSag3)K9nVzOAds2nO)G-qCa2peszu(up--Y)GvOp^I>MQzV+%nx79 z`OkV>(Xi1%Q=GkIty*NMv^7{grGfR)hOeyOR`aLL!Fj@!a;Eo>xo|=4QpNKay<(0SVMV!o-UJEu z%*5DRv5~jpqJ~}Mk#mI>ncTnAt4p=T6pxRhT4N_tf*CR2I>k#Eg*%E&Pu@R7`&31` zbQ;wzYr=rf;XuTRG`^wY6tc7*Bi(ut=DHAX=rz4wtzu+U*fyII9Ij)GkXbLBs3Dc@ zuF39uB6pS$8w*3x;|I5UGD8x__{!}`c8OlxdWBcz@^6`Jt1qVi6UsxNv+L#>UC$C{kk6#4O#sk06gpM-Ka-koB|( ze5fQxcfp-{{nBg4lx~Fb_Ic+SRZjL-ZJI8BdDker^DeaU%YiwZouF+GiKn5rpRW1W zU>XOUp*?|9Hip;Oknx#;B2ZD_%8IQPD>mX~q^CRN&VOUTvKBuzVXJ0j)M>vpM2)oT z=Mbn;HK4@ac^6K3G~|iHV*g-iV|1-yi9?%&9iBMT#f~K{OvH`ds#(i3l^*(3A6L7d z5f?IUsv_fwCwe5ke~d`<5!@PQDWBil-Zua6+H{3+GAr=pQwAZAFQFsnHeMfWJT8A~ zQt}_!xEqyx!;T4lPD!+(dIwo#t2IwM5q_-f`U0mcmq_*Q2P&oRKjHMmh!w)J5L+ga z?}y8?jI7oK1%2}9RZCTHihXkC*<7J~p{A2TPyZ0Ho=8overlpGZ)k5rzZ$1ozmHk^M2O-wiZ%4IaY>v0@=+s*f2gyKh~4(!YroN*<(F)Q;lKDR~`fJ1o-Fq?={T*T?i z2lK6E^U+yx68*q3NXw&EB2>e;RVm7dUuTUzK_e!Ot7q>e(nuw zhV?zs1|vVuvZf%Tephr^_GU){S#g1^>dwa4y4L+ zwoB{q0&-Gzukd0cS3{xrwV+c^i>;i-NV&StK!|;|yBqN`WxLp)Z{YGP51*N=ua_^{ z7zNWaX+9YLj)tdg+pySjXu*G-Ffo%8p~%k_V%M5(R5_8I6K=9|fxPn_*B-5KI^np) z#~%Y_7_qsC63=X~y5@+rXx`}U=LD~WW!HLT;^pKtp?I^pq?!`TvU5(a;M~^UhWjo4 zZ<|hhc}^z>7M64O8LY#G|0EA$akSoyURk!dQk*u!kOgcsT6QeI5!y%O+Y)AEoYQGOM8g}Z>tKCz z)Pq$IS0Zv0iEwF|=@V%%^7ma{?QZPV={G!|*H_|b#8|xj$b`+V-*J0qj?fq@d<1Df z5_Y~`t$NYu2A1#a*$|De4FV_jLqJC3x3oq_4=4sgvRq@4MPsu7-OzaWAb&$^LL9GN z*XGJ2Iy$S%etRp89VxAGd4XqzIP^*`ZjCI8_~zHhK(_p%?3*Y?=PRA^zP0$=QIv|H zgZ^^$BK!QHu+o2f0_Lf-T-QbsMYzQ%}Y6J zYxSKm^FyNk{Q6NNXvOuBaxs24gFIs+`=^q`7ZYg_vETPuLnAE5Vt1RC`c-Bk_YtH~ zB}an9^Mq`dgNN7>Bt^jif;FHPWsBfoAHfNGmqcaf^V3U9Y$fe;9Z_7=GFkM{DudNo zbhlhr8H&ZdzeMos_E!dnwyS@dT6t}of|9>V%=@JV(OOKqR~?2I?2K6Uh|PB{;h zvIM8viGZU`jeP-6=p(9@ZXjW>v9UL4exi|+c47bxWm`&YP*C0&slWELQ6H+!<*eX8 zU*ECJ)zFKRyFWStCj_69FKVw_D7R3}7jLr5?fKyz`6QM(G&lEMrDlplY%ZTLd$l>QC5g|+?& z&y^62PVUW`?cNEEBn4%u!X9frEwFgk7j$YBwDWoM!JKd|GCN0638IqN_79@4Aw=yd7h0K?@4ppY?o&Z`@CD@NTo2D>dw|GyzU6bl#2Q0 zLIrD#lsLhypV<7bY)8T-j?|Di@(k!?F>3*a>h{m#E~Sd4x|ENEKRns2tofVSdp7sc zn5u2tljK^qx~gzf?FQEumK^N-iymc-)`bE zt@o?szya^YiD21Vq0(h@Y$cl4g4j^RD$-hiO_a~)YxS)ETmZg6L7xp*)?01AV-3(*2~!T=Lz3@zvStG zb5sQpX9UwccHWDI(+h=@7FG1i`9;6^LsvA4B!%R&m39Fb=kuS} zl@*sCI+mWNeNU)fVdwfz2&amGPkwu8h6j9ae*C}vBkD@0Ct$ieZgsX_pmMHAkw#|o zgB0W!4XXCvP_eYYuXrOgft_WmL0%A8JuDTz?IFdLylia1FdsMpg=To-tjWF?G^9Ug z4HdfpeZDQwmCaDSA4q51kSVj4#pqIZJVw|~o4nOO&P&j{x!K ztw!urVjOTk2ppuMY3bE5NdQiOiS1d8)9M~@0$9Sh@iy|m-aAM|tXgSn7N3fbScJ~w z*7$!n^ z$IJ6=TPaHOln4h#?Up{(>s6v1yjDLKcCIl?dzp8>y#A!dlKlH8=}?gS};Yq>&A2RgU7r7vsc#?fK>B_sCX8Q*Vcb4P_ z5DLDlfBWb6qL^#;m~_Qx%jJp2I73WUfMF$i9{J@BmDOO0jre4whKOO3h=cx(Cue&< z+XWqCNdy_QOSK~p#zr=r4+gij>`6_AFKPXWAFIQHgsMZ$#=ZY~jcN&8z#*roRjLhcL0j~PVyfeE0Uu6DDYt$w|{7-FP%yCyrI=vF>G60n3u z`WQ)fN5`tA_dA<-**2I}-dp7NeMnHx-Ppl%(QK*mPurjm|CtjE!PTp9z5{mb^)RYk zdU~kbDctB$drkrz*zkkwP+HV{;TJ1eWCA%pH?d~Q2!v@-p`pC%db|B!b1e@RpR|M4uPT#{G# ztgWqYhVvTXN+#H@p!Bgw3vCEw;joj>s|Ef5TK#7&^i3;~wb8o%*slHWo)vSFm<Eut4bBVeA%2(WHCKb>8@XDTlx{lsvS{c+iRQJcdh_6 z4Gb=_hWEN+u3sUvoKHUe;^%jJ;vYk)sHwI%L%ZGv-+%A1_Hx$T9~2g# zUfn`vwm+BHjMv#DOZ`vR;V+F>cCd;UCBLJV=d6D~ekO;X`rbzHijDHSDda|c2g2P| zP!BuEy%@ri-;ff_92?3cnc=;$Aigybu>zb=POj}an3~w)b{WZP?~OJ`h-FWzNL^}| zA=x7y-pj`BZO;msH-v$9=Sq-pYx?r>-Ae5~sg@zp$=bRBa5P<&?u&D{*?e(G+^$SS zs6@Ru^C~v4HD$=Ll8-aq`6>=QAB)4`q?YPVvS(0c+bR}Y11V3;pLebvI>sDN!z7XB zzBnpAn_Ilx1cS5U&%O%J^W`8jI<1fS@4J5PIM1@(5sVym!CL@H2s_82Y-_vX&($?w z0tM3Y^Z9j5eBFdHf6cbHLw%krZdW!k8o41$BRN-a;^aZC627E|#I}UE2xSSb1W9*g z5DwJ9onVW-oh^3ujC9D{aW9hH6G}S6FnJc=%V6J{flWyeEIqGDjTA!d*4IUvlHC_~ zhg2llF{$w-5i7<+hn$bSULOFS7(vhFiJt!c%$gb*JhQhw7^>2gUpFxO+n5+Z3x#|v zF;;4Qzzh;7R-v+co4f{Pxf2stwCo*d_}~IbI}@Bj@CD%!zi5@E>#eR2Iav`~Vq(Nx zOo4bOhP;C9QY*KVC8pDg%ns5PmA3x{Bxok&Zw2koc}#Z4S!U0X8y{^_;`q=Q{V*x+X@vW6P1mHk(Cekj}aSKpSB3KOGO+w zcxVDhsLW`@KHO!4SweQ*AV7wmlh4H$t5y`0f7k3x^j?Tr^j-7@4+}+>lgCVwA}2X+ z-3-q)#0pA#tv0}sjS=wqc$A$JBx9EmxSmj=hH;`!#@k>a^@=SmfQE}b;~@In{F4UG{OVUoGRO{zKGJ@o17o#keF z5qsSQ;0=T9SyJ0Tp_veRZXjIa7p?VCao`cMnramtYnd+}Ge+~?=3E)oyA11A;xHt# zzdN>Xgy!Xbdr16tX0dr=I9okS0YdFBM3LH16(}1UAVgw@r6V3YtT_mejsno8)z=TSXs@{`ZxnYk`;scQL422(T@@D*D(hO=kobFkf8J5#br{m}Yd7kQ<3cb-?j+|dY7wF~6`6aV<&WEcG0?|>F{iJtGun4_R* z%}Pl*KaPLe{xO&(@!&D3KM{~!BV{^`)qrQGh2AkO=J=z$C}c23rlMwZC@H4Ni0f+@T~m!c8SM-Cd=2{a?>*x}Ga&^98MR;6WnZqhfAQlV{RGyXv2#gq?*@l+JQ}j=GDD$mB516YhXfyKV~i6nnY}j$ZI4~R%_`hFs@VyAR(ye8pY*c z|LsiwCJ_0=vE2pt>3)n!>IN^Qa&jQWRPHz;Xg^TE2);FTeb6pWoU1@cY@uSj2&{qm z+Xuf9tde{Mfz^=FwL^{}kww^66O`N29ccFCyTq<)F+0^kEjnEAaj?pBr3+(H+Y&3x z17gH?iK(D?b4ahmYi)-7tXtrC$CDOoWsPvIT;k_d-JbYzcwzQ-NuVX#8rh=_yILCW zCNysAU3UKP8o~^jJpIzaFT-R70|x}8o^yrR$|Jz0YBRJP^O+pMJ^1ZptT=svke=)# zzs+|n8E{eTTv7A#6DJ?DcPpTA8h{Tj9<0_r&n0#~t(?5EUpk7w;7`0gD$wEpg&nvX z|KiCCHuAxPeUF0Y6j@taqlYIH;-ExxP*YRufdfOhPS{y5uhj}Y7+c>bb8@TY*UQ0c#YE7XEpvq8mAaEE z_M4rc5eLH0nY6|^La{vZvL43iWS8!Vnma4ZU>uy5pwq8%ZQ6;0-=M+zneNnHy z7^_6YSdFiug1q9?-&)DbWSXgAz@cHsLnUEI8lJ3q5Nbg~Zv93PY_&U+0^NBA<#V7e zV}z`fYvAuwV5Hk1q-}akqge;gm)K{l@);^gGI~J#=2){uyp<#)4d=yaW@bhZl%>x` z<(Lxmn043s@00)BO7;-i{nm>u5pY>u9ighU|O+^x>^ z@;E`Vm7G(k0)(OX?rL{)D2--Al%-lUzmdpR(yxPM4sqnYczyQ(JNuz*OGOm4gpM|W zM}i!*$xPS57{`DeA*TvlAyu6jk5nLZ-aA4VtknZ0T2C+S*(pT-!Z{%(P zl%kV|GV8y3OOP&531{?O?PM_8C!6zl*il3{XhL!*=(*Ob)19M(iFfPMBU@`BFkdr} zQfP(EiGiQV0AG+^(ER2CEIXq=6c@w&f!(4_aSV(%FNVy{wr*Y#5ziA0Tg)xt+i4L2Fxs*lS>&m0>F) zl3<#LC)h3WlYCtV7@51{EnINTVP2?{D>FVEyk;WVYXr{3NV2i-GjM7Jg8@oPKl__L z`R44t4(-bZ!}9Ibaq55BGyV3F{|#sM|JX;;_K&4H?&y88dhiwFhq$i%SN_%80sjLY C7M>;m literal 0 HcmV?d00001 diff --git a/doc/06_perception/10_sensor_filter_debug.md b/doc/06_perception/10_sensor_filter_debug.md new file mode 100644 index 00000000..83307e48 --- /dev/null +++ b/doc/06_perception/10_sensor_filter_debug.md @@ -0,0 +1,147 @@ +# sensor_filter_debug.py + +**Summary:** [sensor_filter_debug.py](.../code/perception/src/sensor_filter_debug.py): + +The sensor_filter_debug node is responsible for collecting sensor data from the IMU and GNSS and process the data in such a way, that it shows the errors between the real is-state and the measured state. +The data is the shown in multiple rqt_plots. + +--- + +## Author + +Robert Fischer + +## Date + +03.12.2023 + +## Prerequisite + +--- + +- [sensor\_filter\_debug.py](#sensor_filter_debugpy) + - [Author](#author) + - [Date](#date) + - [Prerequisite](#prerequisite) + - [Getting started](#getting-started) + - [Description](#description) + - [Inputs](#inputs) + - [Outputs](#outputs) + + +--- + +## Getting started + +Uncomment the sensor_filter_debug.py node in the [perception.launch](.../code/perception/launch/perception.launch) to start the node. +You can also uncomment the rqt_plots that seem useful to you, or create your own ones from the data published. +You have to add the following sensors to the sensors inside the [dev_objects.json](.../code/agent/config/dev_objects.json): + +```json +{ + "type": "sensor.other.gnss", + "id": "Ideal_GPS", + "spawn_point": { + "x": 0.0, + "y": 0.0, + "z": 1.60 + }, + "noise_alt_stddev": 0.0, + "noise_lat_stddev": 0.0, + "noise_lon_stddev": 0.0, + "noise_alt_bias": 0.0, + "noise_lat_bias": 0.0, + "noise_lon_bias": 0.0 + }, + { + "type": "sensor.other.imu", + "id": "Ideal_IMU", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0 + }, + "noise_accel_stddev_x": 0.0, + "noise_accel_stddev_y": 0.0, + "noise_accel_stddev_z": 0.0, + "noise_gyro_stddev_x": 0.0, + "noise_gyro_stddev_y": 0.0, + "noise_gyro_stddev_z": 0.0 + }, + { + "type": "sensor.other.radar", + "id": "Ideal_RADAR", + "spawn_point": { + "x": 0.7, + "y": 0.4, + "z": 1.60, + "roll": 0.0, + "pitch": 0.0, + "yaw": 45.0 + }, + "horizontal_fov": 30.0, + "vertical_fov": 30.0, + "points_per_second": 1500, + "range": 100.0 + } +``` + +You also have to launch it in dev mode, otherwise the added ideal sensors won't work. +No extra installation needed. + +--- + +## Description + +Running the node provides you with ideal Sensor topics that can be used to debug your sensor filters by giving you ideal values you should aim for. +Right now only the IMU and the GNSS sensor are available for debug. +Debug for the RADAR and LIDAR hasn't been implemented yet. + +An Example of Location Error Output can be seen here: +![Distance from current_pos to ideal_gps_pos (blue) and to carla_pos (red)](.../doc/00_assets/gnss_ohne_rolling_average.png) + +### Inputs + +This node subscribes to the following needed topics: + +- OpenDrive Map: + - `/carla/{role_name}/OpenDRIVE` ([String](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) or `/carla/world_info` ([CarlaWorldInfo](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_msgs/#carlaworldinfomsg)) +- Ideal_IMU: + - `/carla/{role_name}/Ideal_IMU` ([IMU](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html)) +- Ideal_GPS: + - `/carla/{role_name}/Ideal_GPS` ([NavSatFix](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- current agent position: + - `/paf/{role_name}/current_pos` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- current agent heading: + - `/paf/{role_name}/current_heading` ([Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) +- [Carla_API](https://carla.readthedocs.io/en/latest/python_api/) + - `get_location` + +### Outputs + +This node publishes the following topics: + +- Ideal_IMU: + - `/carla/{role_name}/Ideal_IMU` ([IMU](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html)) +- Ideal_GPS: + - `/carla/{role_name}/Ideal_GPS` ([NavSatFix](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- Ideal Odometry: + - `/ideal_odom` ([Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html)) +- Ideal current agent position (calculated from ideal GPS): + - `/paf/{role_name}/idealcurrent_pos` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Ideal current agent heading (calculated from ideal IMU): + - `/paf/{role_name}/current_heading` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Carla Position: + - `/paf/{self.role_name}/carla_current_pos` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Location Error: + - `/paf/{self.role_name}/location_error` ([Float32MultiArray](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/Float32MultiArray.html)) +- Heading Error: + - `/paf/{self.role_name}/heading_error` ([Float32](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Ideal Coordinate Publisher (used to debug [#105](https://github.com/una-auxme/paf23/issues/105)) + - Ideal X Publisher: + - `/paf/{self.role_name}/ideal_x`([Float32MultiArray](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/Float32MultiArray.html)) + - Ideal Y Publisher: + - `/paf/{self.role_name}/ideal_y`([Float32MultiArray](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/Float32MultiArray.html)) diff --git a/doc/06_perception/11_kalman_filter.md b/doc/06_perception/11_kalman_filter.md new file mode 100644 index 00000000..1efc34a1 --- /dev/null +++ b/doc/06_perception/11_kalman_filter.md @@ -0,0 +1,144 @@ +# Kalman Filter + +**Summary:** [kalman_filter.py](.../code/perception/src/kalman_filter.py): + +The Kalman Filter node is responsible for filtering the location and heading data, by using an IMU and GNSS sensor together with the carla speedometer. + +--- + +## Author + +Robert Fischer + +## Date + +03.12.2023 + +## Prerequisite + +--- + +- [Kalman Filter](#kalman-filter) + - [Author](#author) + - [Date](#date) + - [Prerequisite](#prerequisite) + - [Getting started](#getting-started) + - [Description](#description) + - [1. Predict](#1-predict) + - [2. Update](#2-update) + - [3. Publish Data](#3-publish-data) + - [Inputs](#inputs) + - [Outputs](#outputs) + + +--- + +## Getting started + +Right now the Node does not work correctly. It creates topics to publish to, but doesn't yet. +This will be fixed in [#106](https://github.com/una-auxme/paf23/issues/106) + +Uncomment the kalman_filter.py node in the [perception.launch](.../code/perception/launch/perception.launch) to start the node. +You can also uncomment the rqt_plots that seem useful to you. +No extra installation needed. + +--- + +## Description + +Sources to understand the topic better: + +[Visally Explained Kalman Filters](https://www.youtube.com/watch?v=IFeCIbljreY&ab_channel=VisuallyExplained) + +[Understand & Code Kalman Filters](https://www.youtube.com/watch?v=TEKPcyBwEH8&ab_channel=CppMonk) + +Stackoverflow and other useful sites: + +[1](https://stackoverflow.com/questions/47210512/using-pykalman-on-raw-acceleration-data-to-calculate-position), +[2](https://robotics.stackexchange.com/questions/11178/kalman-filter-gps-imu), +[3](https://stackoverflow.com/questions/66167733/getting-3d-position-coordinates-from-an-imu-sensor-on-python), +[4](https://github.com/Janudis/Extended-Kalman-Filter-GPS_IMU) + +This script implements a Kalman Filter. It is a recursive algorithm used to estimate the state of a system that can be modeled with linear equations. +This Kalman Filter uses the location provided by a GNSS sensor (by using the current_pos provided by the [Position Publisher Node](.../code/perception/src/Position_Publisher_Node.py)) +the orientation and angular velocity provided by the IMU sensor and the current speed in the headed direction by the Carla Speedometer. + +```Python +The state vector X is defined as: + [initial_x], + [initial_y], + [yaw], + [v_hy] in direction of heading hy, + [a_hy] in direction of v_hy (heading hy), + [omega_z], +The state transition matrix F is defined as: + A = I + I: Identity Matrix +The measurement matrix H is defined as: + H = [1, 0, 0, 0, 0, 0], + [0, 1, 0, 0, 0, 0], + [0, 0, 1, 0, 0, 0], + [0, 0, 0, 0, 0, 1] +The process covariance matrix Q is defined as: + Q = np.diag([0.005, 0.005, 0.001, 0.0001]) + +``` + +Then 3 Steps are run in the frequency of the `control_loop_rate`: + +### 1. Predict + +```Python + # Update the old state and covariance matrix + self.x_old_est[:, :] = np.copy(self.x_est[:, :]) + self.P_old_est[:, :] = np.copy(self.P_est[:, :]) + + # Predict the next state and covariance matrix + self.x_pred = self.A @ self.x_est[:] # + B @ v[:, k-1] + u + self.P_pred = self.A @ self.P_est[:, :] @ self.A.T + self.Q +``` + +### 2. Update + +```Python + z = np.concatenate((self.z_gps[:], self.z_imu[:])) # Measurementvector + y = z - self.H @ self.x_pred # Measurement residual + S = self.H @ self.P_pred @ self.H.T + self.R # Residual covariance + self.K[:, :] = self.P_pred @ self.H.T @ np.linalg.inv(S) # Kalman gain + self.x_est[:] = self.x_pred + self.K[:, :] @ y # State estimate + # State covariance estimate + self.P_est[:, :] = (np.eye(6) - self.K[:, :] @ self.H) @ self.P_pred +``` + +### 3. Publish Data + +```Python + # Publish the kalman-data: + self.publish_kalman_heading() + self.publish_kalman_location() +``` + +As stated before, the script does not publish viable data yet, which has to be fixed. +This means the predict and update steps might not be correct, because it wasn't possible to test it yet. + +### Inputs + +This node subscribes to the following needed topics: + +- IMU: + - `/carla/{role_name}/Ideal_IMU` ([IMU](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html)) +- GPS: + - `/carla/{role_name}/Ideal_GPS` ([NavSatFix](http://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- current agent position: + - `/paf/{role_name}/current_pos` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Carla Speed: + - `/carla/" + self.role_name + "/Speed` CarlaSpeedometer + +### Outputs + +This node publishes the following topics: + +- Kalman Heading: + - `/paf/{role_name}/kalman_heading` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- Kalman Position: + - `/paf/{self.role_name}/kalman_pos` ([PoseStamped](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) diff --git a/doc/06_perception/Readme.md b/doc/06_perception/Readme.md index 13219e73..f92978c3 100644 --- a/doc/06_perception/Readme.md +++ b/doc/06_perception/Readme.md @@ -3,3 +3,7 @@ This folder contains further documentation of the perception components. ## 1. [Dataset generator](./01_dataset_generator.md) + +## 10. [sensor_filter_debug.py](./10_sensor_filter_debug.md) + +## 11. [Kalman Filter](./11_kalman_filter.md) From 2d7a574c959eef523a9aed45809b07275680f6b8 Mon Sep 17 00:00:00 2001 From: robertik10 Date: Mon, 4 Dec 2023 00:45:47 +0100 Subject: [PATCH 13/14] feat(#78): removed carla API from sensor_filter_debug.py --- code/perception/src/sensor_filter_debug.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index b1c92b79..caba249a 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -15,9 +15,8 @@ from tf.transformations import euler_from_quaternion from std_msgs.msg import Float32MultiArray from xml.etree import ElementTree as eTree - -import carla -import rospy +# import carl____a remove ___ to use +# import rospy # from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 @@ -49,18 +48,19 @@ def __init__(self): # todo: automatically detect town self.transformer = None + # remove comments to use carla # Carla API hero car position # Get parameters from the launch file - host = rospy.get_param('~host', 'carla-simulator') - port = rospy.get_param('~port', 2000) - timeout = rospy.get_param('~timeout', 100.0) + # host = rospy.get_param('~host', 'carla-simulator') + # port = rospy.get_param('~port', 2000) + # timeout = rospy.get_param('~timeout', 100.0) # Connect to the CARLA server - client = carla.Client(host, port) - client.set_timeout(timeout) + # client = carl___a.Client(host, port) + # client.set_timeout(timeout) # Get the world - self.world = client.get_world() + # self.world = client.get_world() # Get the ego vehicle self.vehicle = None From 6ceee1850379fcd469886838813ebbfe422d117e Mon Sep 17 00:00:00 2001 From: robertik10 Date: Mon, 4 Dec 2023 14:02:55 +0100 Subject: [PATCH 14/14] fix: pr comments --- build/docker-compose.yml | 4 ++-- code/agent/config/rviz_config.rviz | 2 +- code/perception/src/dataset_generator.py | 17 ++++++++++++----- code/perception/src/sensor_filter_debug.py | 1 - code/requirements.txt | 1 - doc/06_perception/11_kalman_filter.md | 1 - 6 files changed, 15 insertions(+), 11 deletions(-) diff --git a/build/docker-compose.yml b/build/docker-compose.yml index 1545f945..a68e97c4 100644 --- a/build/docker-compose.yml +++ b/build/docker-compose.yml @@ -57,8 +57,8 @@ services: tty: true shm_size: 2gb #command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/opt/leaderboard/leaderboard/autoagents/npc_agent.py --host=carla-simulator --track=SENSORS" - command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" - #command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" + #command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch" + command: bash -c "sleep 10 && sudo chown -R carla:carla ../code/ && sudo chmod -R a+w ../code/ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP" logging: driver: "local" environment: diff --git a/code/agent/config/rviz_config.rviz b/code/agent/config/rviz_config.rviz index 0d43d6b1..7064cc88 100644 --- a/code/agent/config/rviz_config.rviz +++ b/code/agent/config/rviz_config.rviz @@ -166,7 +166,7 @@ Visualization Manager: Offset: X: 0 Y: 0 - Z: 0 #39 + Z: 39 Pose Color: 255; 85; 255 Pose Style: None Queue Size: 10 diff --git a/code/perception/src/dataset_generator.py b/code/perception/src/dataset_generator.py index 58f5d4b4..fd849d11 100755 --- a/code/perception/src/dataset_generator.py +++ b/code/perception/src/dataset_generator.py @@ -246,15 +246,21 @@ def create_argparse(): help='set up an empty world and spawn ego vehicle', default=False ) + argparser.add_argument( + '--town', + metavar='T', + default='Town12', + help='town to load' + ) return argparser if __name__ == '__main__': - towns = ["Town01", "Town02", "Town03", "Town04", "Town05", "Town06", - "Town07", "Town10", "Town11", "Town12"] - town = towns[2] + towns = {"Town01", "Town02", "Town03", "Town04", "Town05", "Town06", + "Town07", "Town10", "Town11", "Town12"} argparser = create_argparse() args = argparser.parse_args() + town = args.town output_dir = args.output_dir host = args.host port = args.port @@ -262,10 +268,11 @@ def create_argparse(): client = carla.Client(host, port) client.set_timeout(30) - world = client.load_world(town) + world = client.load_world(town) if use_empty_world else client.get_world() world.wait_for_tick() - output_dir = os.path.join(output_dir, town[-2:]) + output_dir = os.path.join(output_dir, world.get_map().name[-2:]) + print("Saving images to {}".format(output_dir)) if use_empty_world: ego_vehicle = setup_empty_world(client) diff --git a/code/perception/src/sensor_filter_debug.py b/code/perception/src/sensor_filter_debug.py index caba249a..6ea53e7a 100755 --- a/code/perception/src/sensor_filter_debug.py +++ b/code/perception/src/sensor_filter_debug.py @@ -17,7 +17,6 @@ from xml.etree import ElementTree as eTree # import carl____a remove ___ to use # import rospy -# from carla_msgs.msg import CarlaLo GPS_RUNNING_AVG_ARGS: int = 10 diff --git a/code/requirements.txt b/code/requirements.txt index 228a7204..c15e4287 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -11,4 +11,3 @@ scipy==1.10.0 xmltodict==0.13.0 py-trees==2.1.6 numpy==1.23.5 -pymap3d==3.0.0 diff --git a/doc/06_perception/11_kalman_filter.md b/doc/06_perception/11_kalman_filter.md index 1efc34a1..8eadb14b 100644 --- a/doc/06_perception/11_kalman_filter.md +++ b/doc/06_perception/11_kalman_filter.md @@ -81,7 +81,6 @@ The measurement matrix H is defined as: [0, 0, 0, 0, 0, 1] The process covariance matrix Q is defined as: Q = np.diag([0.005, 0.005, 0.001, 0.0001]) - ``` Then 3 Steps are run in the frequency of the `control_loop_rate`: